imu_node.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112
  1. #ifndef __IMU_NODE_HH
  2. #define __IMU_NODE_HH
  3. #include "JY901.h"
  4. #include <boost/thread.hpp>
  5. #include "serial/serial.h"
  6. #include <chrono>
  7. #include <iostream>
  8. #include <mutex>
  9. #include <ros/ros.h>
  10. #include <nav_msgs/Odometry.h>
  11. #include <tf/tf.h>
  12. #include <tf/transform_datatypes.h>
  13. #include <tf/transform_broadcaster.h>
  14. #define iBufferSize 50
  15. #define UARTBufferLength 1000
  16. #include "JY901.h"
  17. CJY901 JY901;
  18. class ImuNode
  19. {
  20. public:
  21. ImuNode(std::string port, unsigned long baud);
  22. ~ImuNode();
  23. void publish_data();
  24. protected:
  25. static void thread_get_data(ImuNode *imu_node)
  26. {
  27. int countDown=20;
  28. while ((imu_node->b_connected_ || countDown-- > 0) && !imu_node->b_exit_)
  29. {
  30. // std::cout<<imu_node->my_serial->isOpen()<<std::endl;
  31. if (imu_node->my_serial->isOpen())
  32. {
  33. imu_node->b_connected_ = true;
  34. // std::vector<uint8_t> temp_buffer;
  35. int count = imu_node->my_serial->read(imu_node->p_temp_buf, iBufferSize);
  36. // std::cout<<"count: "<<count<<std::endl;
  37. std::unique_lock<std::mutex> lck(imu_node->mtx);
  38. // end 添加后在范围内
  39. if ((imu_node->end + count) <= UARTBufferLength)
  40. {
  41. // std::cout<<"bbb"<<std::endl;
  42. // std::cout<<"end: "<<imu_node->end<<std::endl;
  43. memcpy((imu_node->p_buffer + imu_node->end), imu_node->p_temp_buf, count);
  44. // std::cout<<"start: "<<imu_node->start<<std::endl;
  45. if (imu_node->start > imu_node->end && imu_node->start <= imu_node->end + count)
  46. {
  47. imu_node->start = imu_node->end + count + 1;
  48. imu_node->start %= UARTBufferLength;
  49. }
  50. imu_node->end += count;
  51. imu_node->end %= UARTBufferLength;
  52. }
  53. // 超出范围
  54. else
  55. {
  56. // std::cout<<"ccc"<<std::endl;
  57. int offset = UARTBufferLength - imu_node->end;
  58. // std::cout<<"offset: "<<offset<<std::endl;
  59. memcpy((imu_node->p_buffer + imu_node->end), imu_node->p_temp_buf, offset);
  60. memcpy(imu_node->p_buffer, (imu_node->p_temp_buf + offset), count - offset);
  61. if (imu_node->start > imu_node->end || (imu_node->start < imu_node->end && imu_node->start < (imu_node->end + count) % UARTBufferLength))
  62. {
  63. imu_node->start = (imu_node->end + count) % UARTBufferLength + 1;
  64. }
  65. imu_node->end += count;
  66. imu_node->end %= UARTBufferLength;
  67. }
  68. }
  69. else
  70. {
  71. imu_node->b_connected_ = false;
  72. }
  73. // std::cout << "count down: " << countDown << std::endl;
  74. usleep(5 * 1000);
  75. }
  76. std::cout << "数据获取线程退出" << std::endl;
  77. };
  78. public:
  79. bool b_exit_;
  80. // 0默认,1正向,2反向
  81. int m_angle_status_[3]={0,0,0};
  82. protected:
  83. bool b_connected_;
  84. std::mutex mtx;
  85. //std::unique_lock<std::mutex> buffer_lock;
  86. serial::Serial *my_serial;
  87. char *p_buffer;
  88. uint8_t *p_temp_buf;
  89. int start,end;
  90. boost::thread* read_thread_ ;
  91. ros::NodeHandle nh_;
  92. ros::Publisher odom_pub_;
  93. tf::Pose last_pose_, curr_pose_;
  94. geometry_msgs::Twist last_vel_, curr_vel_;
  95. ros::Time last_time_, curr_time_, ori_time_;
  96. tf::TransformBroadcaster tf_broadcaster_;
  97. };
  98. #endif