rs_device_bridge.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. #ifndef RS_DEVICE_BRIDGE_HH
  2. #define RS_DEVICE_BRIDGE_HH
  3. /*
  4. * @Author: yct 18202736439@163.com
  5. * @Date: 2023-01-12 14:31:29
  6. * @LastEditors: yct 18202736439@163.com
  7. * @LastEditTime: 2023-01-12 15:14:54
  8. * @FilePath: /puai_wj_2021/velodyne_lidar/velodyne_driver/rs_device_bridge.h
  9. * @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
  10. */
  11. #include "../rslidar/rslidar_driver.h"
  12. #include "velodyne_driver/velodyne_lidar_device.h"
  13. class RS_device_bridge : public Velodyne_lidar_device
  14. {
  15. public:
  16. // 无参构造函数
  17. RS_device_bridge(){}
  18. // 析构函数
  19. ~RS_device_bridge(){}
  20. // 初始化
  21. Error_manager init(velodyne::velodyneLidarParams params)
  22. {
  23. return m_rs_lidar.init(params);
  24. }
  25. // 反初始化
  26. Error_manager uninit()
  27. {
  28. return m_rs_lidar.uninit();
  29. }
  30. // 检查雷达状态,是否正常运行
  31. Error_manager check_status(){return m_rs_lidar.check_status(); }
  32. // 判断是否为待机,如果已经准备好,则可以执行任务。
  33. bool is_ready(){return m_rs_lidar.is_ready(); }
  34. int get_lidar_id() { return m_rs_lidar.get_lidar_id(); }
  35. // 外部调用获取最新带环信息点云,通常用于标定
  36. Error_manager get_new_ring_cloud_and_wait(std::mutex* p_mutex, std::vector<Lidar_point> &cloud_vec,
  37. std::chrono::steady_clock::time_point command_time, int timeout_ms=1500)
  38. {
  39. std::vector<PointT> t_cloud_vec;
  40. Error_manager ec = m_rs_lidar.get_new_ring_cloud_and_wait(p_mutex, t_cloud_vec, command_time, timeout_ms);
  41. cloud_vec.clear();
  42. for (size_t i = 0; i < t_cloud_vec.size(); i++)
  43. {
  44. cloud_vec.push_back(Lidar_point(t_cloud_vec[i].x, t_cloud_vec[i].y, t_cloud_vec[i].z, t_cloud_vec[i].ring, 0, 0.0f, t_cloud_vec[i].intensity, t_cloud_vec[i].timestamp));
  45. }
  46. return ec;
  47. }
  48. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  49. Error_manager get_new_cloud_and_wait(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  50. std::chrono::steady_clock::time_point command_time, int timeout_ms=1500)
  51. {
  52. return m_rs_lidar.get_new_cloud_and_wait(p_mutex, p_cloud, command_time, timeout_ms);
  53. }
  54. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  55. // 注意!!!当前最新点云未成环,或许缺失数据
  56. Error_manager get_current_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  57. std::chrono::steady_clock::time_point command_time)
  58. {
  59. return m_rs_lidar.get_current_cloud(p_mutex, p_cloud, command_time);
  60. }
  61. //外部调用获取最新的点云, 如果没有就会报错, 不会等待
  62. Error_manager get_last_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  63. std::chrono::steady_clock::time_point command_time)
  64. {
  65. return m_rs_lidar.get_last_cloud(p_mutex, p_cloud, command_time);
  66. }
  67. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  68. //注:函数内部不加锁, 由外部统一加锁.
  69. Error_manager get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  70. std::chrono::steady_clock::time_point command_time)
  71. {
  72. return m_rs_lidar.get_last_cloud(p_cloud, command_time);
  73. }
  74. public:
  75. Velodyne_lidar_device_status get_status(){return Velodyne_lidar_device_status(m_rs_lidar.get_status());}
  76. void updata_status(){m_rs_lidar.update_status();}
  77. protected:
  78. void execute_thread_fun(){}
  79. // 获取点云线程函数
  80. void capture_thread_fun(){}
  81. // 解析点云线程函数
  82. void parse_thread_fun(){}
  83. protected:
  84. RS_lidar_device m_rs_lidar;
  85. };
  86. #endif