wanji_716N_device.h 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. /*
  2. * @Author: yct 18202736439@163.com
  3. * @Date: 2022-09-22 18:00:51
  4. * @LastEditors: yct 18202736439@163.com
  5. * @LastEditTime: 2022-09-25 22:10:59
  6. * @FilePath: /puai_wj_2021/wanji_lidar/wanji_716N_device.h
  7. * @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
  8. */
  9. #ifndef WJ_716N_ENCAPSULATION_HH
  10. #define WJ_716N_ENCAPSULATION_HH
  11. #include <chrono>
  12. #include <mutex>
  13. #include <thread>
  14. #include <atomic>
  15. #include <string>
  16. #include <unistd.h>
  17. #include "glog/logging.h"
  18. #include "async_client.h"
  19. #include "wj_716N_lidar_protocol.h"
  20. #include "wj_lidar_conf.pb.h"
  21. class Wanji_716N_lidar_device
  22. {
  23. public:
  24. //万集设备身状态
  25. enum Wanji_716N_device_status
  26. {
  27. E_UNKNOWN = 0, //未知
  28. E_READY = 1, //正常待机
  29. E_DISCONNECT = 2, //断连
  30. E_BUSY = 3, //工作正忙
  31. E_FAULT =10, //故障
  32. };
  33. public:
  34. // 无参构造函数
  35. Wanji_716N_lidar_device();
  36. // 析构函数
  37. ~Wanji_716N_lidar_device();
  38. // 初始化
  39. Error_manager init(wj::wjLidarParams params);
  40. //反初始化
  41. Error_manager uninit();
  42. //检查雷达状态,是否正常运行
  43. Error_manager check_status();
  44. //判断是否为待机,如果已经准备好,则可以执行任务。
  45. bool is_ready();
  46. int get_lidar_id() { return m_lidar_id; }
  47. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  48. Error_manager get_new_cloud_and_wait(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  49. std::chrono::system_clock::time_point command_time, int timeout_ms=1500);
  50. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  51. Error_manager get_current_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  52. std::chrono::system_clock::time_point command_time);
  53. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  54. Error_manager get_last_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  55. std::chrono::system_clock::time_point command_time);
  56. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  57. //注:函数内部不加锁, 由外部统一加锁.
  58. Error_manager get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  59. std::chrono::system_clock::time_point command_time);
  60. public:
  61. Wanji_716N_device_status get_status();
  62. protected:
  63. void updata_status();
  64. // //mp_laser_manager_thread 线程执行函数,
  65. // //thread_work 内部线程负责获取点云结果
  66. // void execute_thread_fun();
  67. protected:
  68. // 雷达编号
  69. int m_lidar_id;
  70. //状态
  71. Wanji_716N_device_status m_wanji_lidar_device_status; //万集设备身状态
  72. //子模块
  73. Async_Client m_async_client; //异步客户端, 负责雷达通信, 接受雷达数据
  74. wj_716N_lidar_protocol m_protocol; // 万集雷达协议
  75. //中间缓存
  76. Thread_safe_queue<Binary_buf*> m_communication_data_queue; //通信数据队列
  77. //任务执行线程
  78. std::thread* mp_execute_thread; //执行的线程指针,内存由本类管理
  79. Thread_condition m_execute_condition; //执行的条件变量
  80. };
  81. #endif // !WJ_716N_ENCAPSULATION_HH