wj_lidar_encapsulation.h 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  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 "../tool/StdCondition.h"
  6. #include "../error_code/error_code.h"
  7. using namespace wj_lidar;
  8. class Wj_lidar_encapsulation{
  9. public:
  10. // 无参构造函数
  11. Wj_lidar_encapsulation();
  12. // 析构函数
  13. ~Wj_lidar_encapsulation();
  14. // 初始化
  15. Error_manager initialize(wj::wjLidarParams params);
  16. // 外部调用获取点云
  17. Error_manager get_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud, std::chrono::steady_clock::time_point command_time, int timeout_milli=1500);
  18. // 获取连接状态
  19. bool get_connection_status();
  20. // 获取初始化情况
  21. bool get_initialize_status();
  22. private:
  23. // 初始化雷达连接线程函数
  24. void static init_tcp_connection(const char* addr,int port,Async_Client **client_,fundata_t fundata_, Wj_lidar_encapsulation* p_handle);
  25. // 万集雷达协议,数据获取回调
  26. static void read_callback(const char* data,const int len, const void *handle);
  27. // 连接与异步读写线程创建
  28. Error_manager boost_tcp_init_connection(const char* addr,int port,Async_Client **client_,fundata_t fundata_);
  29. // // 异步写入
  30. // Error_manager boost_tcp_async_send(Async_Client *client_ ,const char* msg,const int len);
  31. // // 异步读取
  32. // Error_manager boost_tcp_async_read(Async_Client *client_ );
  33. private:
  34. Async_Client* mp_client; // 异步客户端句柄
  35. Wj_716_lidar_protocol* mp_protocol; // 万集雷达协议句柄
  36. std::atomic<bool> mb_initialized; // 初始化Flag
  37. std::string m_ip; // IP地址
  38. int m_port; // 端口
  39. // wj::wjLidarParams m_wj_params; // 万集参数
  40. std::thread* m_client_thread; // 异步读取线程
  41. boost::asio::io_service m_io_service; // io服务
  42. std::atomic<bool> mb_exit; // 是否需要关闭
  43. };
  44. #endif // !WJ_LIDAR_ENCAPSULATION_HH