rslidar_driver.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307
  1. #include "rslidar_driver.h"
  2. // 万集雷达封装类构造函数
  3. RS_lidar_device::RS_lidar_device()
  4. {
  5. m_rs_lidar_device_status = E_UNKNOWN;
  6. mb_exit_process = false;
  7. }
  8. // 万集雷达封装类析构函数
  9. RS_lidar_device::~RS_lidar_device()
  10. {
  11. uninit();
  12. }
  13. // 初始化
  14. Error_manager RS_lidar_device::init(velodyne::velodyneLidarParams params)
  15. {
  16. m_params = params;
  17. Error_manager t_error;
  18. LOG(INFO) << " RS_lidar_device::init " << this;
  19. m_rs_lidar_device_status = E_UNKNOWN;
  20. m_rs_protocol_status = E_UNKNOWN;
  21. m_lidar_id = params.lidar_id();
  22. // 设置雷达内参矩阵
  23. Eigen::AngleAxisd rot_x = Eigen::AngleAxisd(params.calib().r()*M_PI/180.0, Eigen::Vector3d::UnitX());
  24. Eigen::AngleAxisd rot_y = Eigen::AngleAxisd(params.calib().p()*M_PI/180.0, Eigen::Vector3d::UnitY());
  25. Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(params.calib().y()*M_PI/180.0, Eigen::Vector3d::UnitZ());
  26. Eigen::Vector3d trans(params.calib().cx(), params.calib().cy(), params.calib().cz());
  27. m_calib_matrix << rot_x.toRotationMatrix() * rot_y.toRotationMatrix() * rot_z.toRotationMatrix(), trans, 0.0, 0.0, 0.0, 1.0;
  28. // LOG(INFO) <<"lidar "<<m_lidar_id<<",,,\n"<< rot_x.toRotationMatrix()<<"------------------\n"<<rot_y.toRotationMatrix()<<"-----------------\n"<<rot_z.toRotationMatrix()<<"---------------\n"<<m_calib_matrix;
  29. m_lidar_params.input_type = InputType::ONLINE_LIDAR;
  30. m_lidar_params.input_param.msop_port = params.port(); ///< Set the lidar msop port number, the default is 6699
  31. m_lidar_params.input_param.difop_port = params.difop(); ///< Set the lidar difop port number, the default is 7788
  32. // m_lidar_params.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788
  33. m_lidar_params.decoder_param.min_distance = params.min_range();
  34. m_lidar_params.decoder_param.max_distance = params.max_range();
  35. m_lidar_params.decoder_param.start_angle = params.min_angle();
  36. m_lidar_params.decoder_param.end_angle = params.max_angle();
  37. m_lidar_params.decoder_param.dense_points = true;
  38. // if(params.model() == "HELIOS16")
  39. m_lidar_params.lidar_type = LidarType::RSHELIOS_16P; ///< Set the lidar type. Make sure this type is correct
  40. // 驱动初始化
  41. m_lidar_driver.regPointCloudCallback(std::bind(&RS_lidar_device::driverGetPointCloudFromCallerCallback, this), std::bind(&RS_lidar_device::driverReturnPointCloudToCallerCallback, this, std::placeholders::_1)); ///< Register the point cloud callback functions
  42. m_lidar_driver.regExceptionCallback(std::bind(&RS_lidar_device::exceptionCallback, this, std::placeholders::_1)); ///< Register the exception callback function
  43. if (!m_lidar_driver.init(m_lidar_params)) ///< Call the init function
  44. {
  45. LOG(WARNING) << "Driver Initialize Error...";
  46. t_error = Error_manager(Error_code::VELODYNE_LIDAR_UNINITIALIZED, Error_level::MAJOR_ERROR,
  47. (std::string("RS_lidar_device::init driver error ")+std::to_string(params.port())).c_str());
  48. return t_error;
  49. }
  50. mp_cloud_handle_thread = new std::thread(std::bind(&RS_lidar_device::processCloud, this));
  51. m_lidar_driver.start();
  52. m_rs_protocol_status = E_READY;
  53. //初始化雷达通信模块
  54. std::string t_ip = params.ip();
  55. int t_port = params.port();
  56. m_rs_lidar_device_status = E_READY;
  57. LOG(INFO) << "rslidar device "<< m_lidar_params.input_param.msop_port<<" initialized.\n";
  58. m_lidar_params.print();
  59. return t_error;
  60. }
  61. //反初始化
  62. Error_manager RS_lidar_device::uninit()
  63. {
  64. mb_exit_process = true;
  65. if(mp_cloud_handle_thread != nullptr)
  66. {
  67. if(mp_cloud_handle_thread->joinable())
  68. mp_cloud_handle_thread->join();
  69. delete(mp_cloud_handle_thread);
  70. mp_cloud_handle_thread = nullptr;
  71. }
  72. m_lidar_driver.stop();
  73. if (m_rs_lidar_device_status != E_FAULT)
  74. {
  75. m_rs_lidar_device_status = E_UNKNOWN;
  76. }
  77. return Error_code::SUCCESS;
  78. }
  79. //检查雷达状态,是否正常运行
  80. Error_manager RS_lidar_device::check_status()
  81. {
  82. update_status();
  83. if (m_rs_lidar_device_status == E_READY)
  84. {
  85. return Error_code::SUCCESS;
  86. }
  87. else if (m_rs_lidar_device_status == E_BUSY)
  88. {
  89. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
  90. " RS_lidar_device::check_status() error ");
  91. }
  92. else
  93. {
  94. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_STATUS_ERROR, Error_level::MINOR_ERROR,
  95. " RS_lidar_device::check_status() error ");
  96. }
  97. return Error_code::SUCCESS;
  98. }
  99. //判断是否为待机,如果已经准备好,则可以执行任务。
  100. bool RS_lidar_device::is_ready()
  101. {
  102. update_status();
  103. return m_rs_lidar_device_status == E_READY;
  104. }
  105. Error_manager RS_lidar_device::get_new_ring_cloud_and_wait(std::mutex *p_mutex, std::vector<PointT> &cloud_vec,
  106. std::chrono::steady_clock::time_point command_time, int timeout_ms)
  107. {
  108. if(p_mutex == nullptr)
  109. {
  110. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  111. " POINTER IS NULL ");
  112. }
  113. //判断是否超时
  114. while (std::chrono::steady_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
  115. {
  116. //获取指令时间之后的点云, 如果没有就会循环
  117. if (m_capture_time > command_time)
  118. {
  119. std::unique_lock<std::mutex> lck(*p_mutex);
  120. {
  121. cloud_vec.clear();
  122. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  123. if (m_ring_cloud.size() <= 0)
  124. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  125. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  126. {
  127. cloud_vec.assign(m_ring_cloud.begin(), m_ring_cloud.end());
  128. }
  129. }
  130. return SUCCESS;
  131. }
  132. //等1ms
  133. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  134. }
  135. //超时退出就报错
  136. return Error_manager(Error_code::VELODYNE_LIDAR_GET_CLOUD_TIMEOUT, Error_level::MINOR_ERROR,
  137. " RS_lidar_device::get_new_ring_cloud_and_wait error ");
  138. }
  139. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  140. Error_manager RS_lidar_device::get_new_cloud_and_wait(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  141. std::chrono::steady_clock::time_point command_time, int timeout_ms)
  142. {
  143. if (p_mutex == NULL || p_cloud.get() == NULL)
  144. {
  145. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  146. " POINTER IS NULL ");
  147. }
  148. //判断是否超时
  149. while (std::chrono::steady_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
  150. {
  151. //获取指令时间之后的点云, 如果没有就会循环
  152. if (m_capture_time > command_time)
  153. {
  154. std::unique_lock<std::mutex> lck(*p_mutex);
  155. {
  156. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  157. if (m_ring_cloud.size() <= 0)
  158. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  159. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  160. {
  161. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  162. }
  163. }
  164. return SUCCESS;
  165. }
  166. //else 等待下一次数据更新
  167. //等1ms
  168. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  169. }
  170. //超时退出就报错
  171. return Error_manager(Error_code::VELODYNE_LIDAR_GET_CLOUD_TIMEOUT, Error_level::MINOR_ERROR,
  172. " RS_lidar_device::get_new_cloud_and_wait error ");
  173. }
  174. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  175. Error_manager RS_lidar_device::get_current_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  176. std::chrono::steady_clock::time_point command_time)
  177. {
  178. if (p_mutex == NULL || p_cloud.get() == NULL)
  179. {
  180. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  181. " POINTER IS NULL ");
  182. }
  183. //获取指令时间之后的点云, 如果没有就会报错, 不会等待
  184. if (m_capture_time > command_time)
  185. {
  186. std::unique_lock<std::mutex> lck(*p_mutex);
  187. {
  188. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  189. if (m_ring_cloud.size() <= 0)
  190. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  191. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  192. {
  193. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  194. }
  195. }
  196. return SUCCESS;
  197. }
  198. else
  199. {
  200. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  201. " RS_lidar_device::get_current_cloud error ");
  202. }
  203. }
  204. //外部调用获取最新的点云, 如果没有就会报错, 不会等待
  205. Error_manager RS_lidar_device::get_last_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  206. std::chrono::steady_clock::time_point command_time)
  207. {
  208. if (p_mutex == NULL || p_cloud.get() == NULL)
  209. {
  210. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  211. " POINTER IS NULL ");
  212. }
  213. if (m_capture_time > command_time - std::chrono::milliseconds(int(60000.0/(m_params.rpm()*0.5))))
  214. {
  215. std::unique_lock<std::mutex> lck(*p_mutex);
  216. {
  217. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  218. if (m_ring_cloud.size() <= 0)
  219. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  220. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  221. {
  222. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  223. }
  224. }
  225. return SUCCESS;
  226. }
  227. else
  228. {
  229. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  230. " RS_lidar_device::get_current_cloud error ");
  231. }
  232. }
  233. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  234. //注:函数内部不加锁, 由外部统一加锁.
  235. Error_manager RS_lidar_device::get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  236. std::chrono::steady_clock::time_point command_time)
  237. {
  238. if (p_cloud.get() == NULL)
  239. {
  240. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  241. " POINTER IS NULL ");
  242. }
  243. if (m_capture_time > command_time - std::chrono::milliseconds(int(60000.0/(m_params.rpm()*0.5))))
  244. {
  245. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  246. if (m_ring_cloud.size() <= 0)
  247. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  248. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  249. {
  250. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  251. }
  252. return SUCCESS;
  253. }
  254. else
  255. {
  256. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  257. " RS_lidar_device::get_current_cloud error ");
  258. }
  259. }
  260. RS_lidar_device::RS_lidar_device_status RS_lidar_device::get_status()
  261. {
  262. update_status();
  263. return m_rs_lidar_device_status;
  264. }
  265. void RS_lidar_device::update_status()
  266. {
  267. if (m_rs_protocol_status == E_FAULT)
  268. {
  269. m_rs_lidar_device_status = E_FAULT;
  270. }
  271. else if(m_rs_protocol_status == E_BUSY)
  272. {
  273. m_rs_lidar_device_status = E_BUSY;
  274. }
  275. else if (m_rs_protocol_status == E_READY)
  276. {
  277. m_rs_lidar_device_status = E_READY;
  278. }
  279. else
  280. {
  281. // LOG(WARNING)<<"unknown????? "<<m_rs_socket_status<<", "<<m_rs_protocol_status;
  282. m_rs_lidar_device_status = E_UNKNOWN;
  283. }
  284. }