rslidar_driver.h 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215
  1. #ifndef RS_LIDAR_ENCAPSULATION_HH
  2. #define RS_LIDAR_ENCAPSULATION_HH
  3. #include <iostream>
  4. #include <thread>
  5. #include <mutex>
  6. #include <chrono>
  7. #include <functional>
  8. #include "../error_code/error_code.h"
  9. #include "../tool/binary_buf.h"
  10. #include "../tool/thread_safe_queue.h"
  11. #include "../tool/thread_condition.h"
  12. #include <Eigen/Core>
  13. #include <Eigen/Geometry>
  14. #include <pcl/point_types.h>
  15. #include <pcl/point_cloud.h>
  16. #include <glog/logging.h>
  17. #include <rs_driver/api/lidar_driver.hpp>
  18. #ifdef ENABLE_PCL_POINTCLOUD
  19. #include <rs_driver/msg/pcl_point_cloud_msg.hpp>
  20. #else
  21. #include <rs_driver/msg/point_cloud_msg.hpp>
  22. #endif
  23. #include "../velodyne_lidar/velodyne_config.pb.h"
  24. using namespace robosense::lidar;
  25. typedef PointXYZIRT PointT;
  26. typedef PointCloudT<PointT> PointCloudMsg;
  27. class RS_lidar_device
  28. {
  29. public:
  30. //万集设备身状态
  31. enum RS_lidar_device_status
  32. {
  33. E_UNKNOWN = 0, //未知
  34. E_READY = 1, //正常待机
  35. E_DISCONNECT = 2, //断连
  36. E_BUSY = 3, //工作正忙
  37. E_FAULT =10, //故障
  38. };
  39. public:
  40. // 无参构造函数
  41. RS_lidar_device();
  42. // 析构函数
  43. ~RS_lidar_device();
  44. // ************************* rslidar driver callbacks *******************************
  45. // @brief point cloud callback function. The caller should register it to the lidar driver.
  46. // Via this fucntion, the driver gets an free/unused point cloud message from the caller.
  47. // @param msg The free/unused point cloud message.
  48. //
  49. std::shared_ptr<PointCloudMsg> driverGetPointCloudFromCallerCallback(void)
  50. {
  51. // std::cout<<"get cloud from caller callback"<<std::endl;
  52. // Note: This callback function runs in the packet-parsing/point-cloud-constructing thread of the driver,
  53. // so please DO NOT do time-consuming task here.
  54. std::shared_ptr<PointCloudMsg> msg = free_cloud_queue.pop();
  55. if (msg.get() != NULL)
  56. {
  57. return msg;
  58. }
  59. return std::make_shared<PointCloudMsg>();
  60. }
  61. //
  62. // @brief point cloud callback function. The caller should register it to the lidar driver.
  63. // Via this function, the driver gets/returns a stuffed point cloud message to the caller.
  64. // @param msg The stuffed point cloud message.
  65. //
  66. void driverReturnPointCloudToCallerCallback(std::shared_ptr<PointCloudMsg> msg)
  67. {
  68. // std::cout<<"return point callback"<<std::endl;
  69. // Note: This callback function runs in the packet-parsing/point-cloud-constructing thread of the driver,
  70. // so please DO NOT do time-consuming task here. Instead, process it in caller's own thread. (see processCloud() below)
  71. // stuffed_cloud_queue.push(msg);
  72. stuffed_cloud_queue.push(msg);
  73. }
  74. //
  75. // @brief exception callback function. The caller should register it to the lidar driver.
  76. // Via this function, the driver inform the caller that something happens.
  77. // @param code The error code to represent the error/warning/information
  78. //
  79. void exceptionCallback(const Error &code)
  80. {
  81. // std::cout<<"exception callback"<<std::endl;
  82. // Note: This callback function runs in the packet-receving and packet-parsing/point-cloud_constructing thread of the driver,
  83. // so please DO NOT do time-consuming task here.
  84. if(ERRCODE_MSOPTIMEOUT == code.error_code)
  85. {
  86. m_rs_lidar_device_status = E_DISCONNECT;
  87. }else if(ERRCODE_SUCCESS == code.error_code)
  88. {
  89. m_rs_lidar_device_status = E_READY;
  90. m_rs_protocol_status = E_READY;
  91. // RS_WARNING << code.toString() << RS_REND;
  92. }else if(code.error_code_type == ErrCodeType::WARNING_CODE || code.error_code_type == ErrCodeType::ERROR_CODE)
  93. {
  94. m_rs_lidar_device_status = E_FAULT;
  95. m_rs_protocol_status = E_FAULT;
  96. // RS_WARNING << code.toString() << RS_REND;
  97. }
  98. RS_WARNING << code.toString() << RS_REND;
  99. }
  100. void processCloud(void)
  101. {
  102. while (!mb_exit_process)
  103. {
  104. usleep(1);
  105. std::shared_ptr<PointCloudMsg> msg = stuffed_cloud_queue.popWait();
  106. if (msg.get() == NULL)
  107. {
  108. continue;
  109. }
  110. m_capture_time = std::chrono::steady_clock::now();
  111. // RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND;
  112. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  113. m_ring_cloud.clear();
  114. for (size_t i = 0; i < msg->points.size(); i++)
  115. {
  116. Eigen::Vector4d point{msg->points[i].x, msg->points[i].y, msg->points[i].z, 1};
  117. point = m_calib_matrix * point;
  118. point.x() = point.x() / point.w();
  119. point.y() = point.y() / point.w();
  120. point.z() = point.z() / point.w();
  121. msg->points[i].x = point.x();
  122. msg->points[i].y = point.y();
  123. msg->points[i].z = point.z();
  124. m_ring_cloud.push_back(msg->points[i]);
  125. }
  126. free_cloud_queue.push(msg);
  127. }
  128. }
  129. // 初始化
  130. Error_manager init(velodyne::velodyneLidarParams params);
  131. //反初始化
  132. Error_manager uninit();
  133. //检查雷达状态,是否正常运行
  134. Error_manager check_status();
  135. //判断是否为待机,如果已经准备好,则可以执行任务。
  136. bool is_ready();
  137. int get_lidar_id() { return m_lidar_id; }
  138. // 外部调用获取最新带环信息点云,通常用于标定
  139. Error_manager get_new_ring_cloud_and_wait(std::mutex* p_mutex, std::vector<PointT> &cloud_vec,
  140. std::chrono::steady_clock::time_point command_time, int timeout_ms=1500);
  141. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  142. Error_manager get_new_cloud_and_wait(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  143. std::chrono::steady_clock::time_point command_time, int timeout_ms=1500);
  144. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  145. // 注意!!!当前最新点云未成环,或许缺失数据
  146. Error_manager get_current_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  147. std::chrono::steady_clock::time_point command_time);
  148. //外部调用获取最新的点云, 如果没有就会报错, 不会等待
  149. Error_manager get_last_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  150. std::chrono::steady_clock::time_point command_time);
  151. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  152. //注:函数内部不加锁, 由外部统一加锁.
  153. Error_manager get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  154. std::chrono::steady_clock::time_point command_time);
  155. RS_lidar_device_status get_status();
  156. void update_status();
  157. protected:
  158. //状态
  159. RS_lidar_device_status m_rs_lidar_device_status; //设备状态
  160. RS_lidar_device_status m_rs_protocol_status;
  161. // 雷达编号
  162. int m_lidar_id;
  163. // 雷达配置
  164. velodyne::velodyneLidarParams m_params;
  165. RSDriverParam m_lidar_params;
  166. LidarDriver<PointCloudMsg> m_lidar_driver; ///< Declare the driver object
  167. // 空点云缓存
  168. SyncQueue<std::shared_ptr<PointCloudMsg>> free_cloud_queue;
  169. SyncQueue<std::shared_ptr<PointCloudMsg>> stuffed_cloud_queue;
  170. bool mb_exit_process;
  171. std::thread* mp_cloud_handle_thread;
  172. std::mutex m_cloud_mutex;
  173. // 完整可获取点云
  174. std::vector<PointT> m_ring_cloud;
  175. // 获取点云时间
  176. std::chrono::steady_clock::time_point m_capture_time;
  177. // 点云内参齐次矩阵
  178. Eigen::Matrix4d m_calib_matrix;
  179. };
  180. #endif // !RS_LIDAR_ENCAPSULATION_HH