wanji_716N_device.h 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  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. #pragma once
  10. #include <chrono>
  11. #include <mutex>
  12. #include <thread>
  13. #include <atomic>
  14. #include <string>
  15. #include <unistd.h>
  16. #include <glog/logging.h>
  17. #include "async_client.h"
  18. #include "wj_716N_lidar_protocol.h"
  19. class Wanji_716N_lidar_device {
  20. public:
  21. //万集设备身状态
  22. enum Wanji_716N_device_status {
  23. E_UNKNOWN = 0, //未知
  24. E_READY = 1, //正常待机
  25. E_DISCONNECT = 2, //断连
  26. E_BUSY = 3, //工作正忙
  27. E_FAULT = 10, //故障
  28. };
  29. public:
  30. Wanji_716N_lidar_device();
  31. ~Wanji_716N_lidar_device();
  32. // 初始化
  33. Error_manager init(const std::string& ip, int port,
  34. Point2D_tool::Polar_coordinates_box t_polar_coordinates_box,
  35. Point2D_tool::Point2D_box t_point2D_box,
  36. Point2D_tool::Point2D_transform t_point2D_transform);
  37. //反初始化
  38. Error_manager uninit();
  39. //检查雷达状态,是否正常运行
  40. Error_manager check_status();
  41. //判断是否为待机,如果已经准备好,则可以执行任务。
  42. bool is_ready();
  43. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  44. Error_manager get_new_cloud_and_wait(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  45. std::chrono::system_clock::time_point command_time, int timeout_ms = 1500);
  46. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  47. Error_manager get_current_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  48. std::chrono::system_clock::time_point command_time);
  49. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  50. Error_manager get_last_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  51. std::chrono::system_clock::time_point command_time);
  52. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  53. //注:函数内部不加锁, 由外部统一加锁.
  54. Error_manager get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  55. std::chrono::system_clock::time_point command_time);
  56. public:
  57. Wanji_716N_device_status get_status();
  58. protected:
  59. void updata_status();
  60. protected:
  61. //状态
  62. Wanji_716N_device_status m_wanji_lidar_device_status; //万集设备身状态
  63. //子模块
  64. Async_Client m_async_client; //异步客户端, 负责雷达通信, 接受雷达数据
  65. wj_716N_lidar_protocol m_protocol; // 万集雷达协议
  66. //中间缓存
  67. Thread_safe_queue<Binary_buf *> m_communication_data_queue; //通信数据队列
  68. //任务执行线程
  69. std::thread *mp_execute_thread; //执行的线程指针,内存由本类管理
  70. Thread_condition m_execute_condition; //执行的条件变量
  71. };