wanji_lidar_device.h 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100
  1. #ifndef WJ_LIDAR_ENCAPSULATION_HH
  2. #define WJ_LIDAR_ENCAPSULATION_HH
  3. #include "async_client.h"
  4. #include "wj_716_lidar_protocol.h"
  5. #include "../error_code/error_code.h"
  6. #include "../tool/binary_buf.h"
  7. #include "../tool/thread_safe_queue.h"
  8. #include "wanji_lidar_scan_task.h"
  9. class Wanji_lidar_device
  10. {
  11. public:
  12. //万集设备身状态
  13. enum Wanji_lidar_device_status
  14. {
  15. E_UNKNOWN = 0, //未知
  16. E_READY = 1, //正常待机
  17. E_DISCONNECT = 2, //断连
  18. E_BUSY = 3, //工作正忙
  19. E_FAULT =10, //故障
  20. };
  21. public:
  22. // 无参构造函数
  23. Wanji_lidar_device();
  24. // 析构函数
  25. ~Wanji_lidar_device();
  26. // 初始化
  27. Error_manager init(wj::wjLidarParams params);
  28. //反初始化
  29. Error_manager uninit();
  30. //对外的接口函数,负责接受并处理任务单,
  31. Error_manager execute_task(Task_Base* p_wanji_lidar_scan_task);
  32. //检查雷达状态,是否正常运行
  33. Error_manager check_status();
  34. //结束任务单,里面会根据任务的故障等级修正雷达管理模块的状态和任务单的状态
  35. Error_manager end_task();
  36. //取消任务单,由发送方提前取消任务单
  37. Error_manager cancel_task(Task_Base* p_wanji_lidar_scan_task);
  38. //判断是否为待机,如果已经准备好,则可以执行任务。
  39. bool is_ready();
  40. int get_lidar_id() { return m_lidar_id; }
  41. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  42. Error_manager get_new_cloud_and_wait(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  43. std::chrono::system_clock::time_point command_time, int timeout_ms=1500);
  44. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  45. Error_manager get_current_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  46. std::chrono::system_clock::time_point command_time);
  47. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  48. Error_manager get_last_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  49. std::chrono::system_clock::time_point command_time);
  50. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  51. //注:函数内部不加锁, 由外部统一加锁.
  52. Error_manager get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  53. std::chrono::system_clock::time_point command_time);
  54. public:
  55. Wanji_lidar_device_status get_status();
  56. protected:
  57. void updata_status();
  58. //mp_laser_manager_thread 线程执行函数,
  59. //thread_work 内部线程负责获取点云结果
  60. void execute_thread_fun();
  61. protected:
  62. // 雷达编号
  63. int m_lidar_id;
  64. //状态
  65. Wanji_lidar_device_status m_wanji_lidar_device_status; //万集设备身状态
  66. //子模块
  67. Async_Client m_async_client; //异步客户端, 负责雷达通信, 接受雷达数据
  68. Wj_716_lidar_protocol m_protocol; // 万集雷达协议
  69. //中间缓存
  70. Thread_safe_queue<Binary_buf*> m_communication_data_queue; //通信数据队列
  71. //任务执行线程
  72. std::thread* mp_execute_thread; //执行的线程指针,内存由本类管理
  73. Thread_condition m_execute_condition; //执行的条件变量
  74. Wanji_lidar_scan_task * mp_wanji_lidar_scan_task; //雷达设备任务单的指针,内存由发送方管理。
  75. };
  76. #endif // !WJ_LIDAR_ENCAPSULATION_HH