#ifndef WJ_LIDAR_ENCAPSULATION_HH #define WJ_LIDAR_ENCAPSULATION_HH #include "async_client.h" #include "wj_716_lidar_protocol.h" #include "../tool/StdCondition.h" #include "../error_code/error_code.h" using namespace wj_lidar; class Wj_lidar_encapsulation{ public: // 无参构造函数 Wj_lidar_encapsulation(); // 析构函数 ~Wj_lidar_encapsulation(); // 初始化 Error_manager initialize(wj::wjLidarParams params); // 外部调用获取点云 Error_manager get_cloud(pcl::PointCloud::Ptr& cloud, std::chrono::steady_clock::time_point command_time, int timeout_milli=1500); // 获取连接状态 bool get_connection_status(); // 获取初始化情况 bool get_initialize_status(); private: // 初始化雷达连接线程函数 void static init_tcp_connection(const char* addr,int port,Async_Client **client_,fundata_t fundata_, Wj_lidar_encapsulation* p_handle); // 万集雷达协议,数据获取回调 static void read_callback(const char* data,const int len, const void *handle); // 连接与异步读写线程创建 Error_manager boost_tcp_init_connection(const char* addr,int port,Async_Client **client_,fundata_t fundata_); // // 异步写入 // Error_manager boost_tcp_async_send(Async_Client *client_ ,const char* msg,const int len); // // 异步读取 // Error_manager boost_tcp_async_read(Async_Client *client_ ); private: Async_Client* mp_client; // 异步客户端句柄 Wj_716_lidar_protocol* mp_protocol; // 万集雷达协议句柄 std::atomic mb_initialized; // 初始化Flag std::string m_ip; // IP地址 int m_port; // 端口 // wj::wjLidarParams m_wj_params; // 万集参数 std::thread* m_client_thread; // 异步读取线程 boost::asio::io_service m_io_service; // io服务 std::atomic mb_exit; // 是否需要关闭 }; #endif // !WJ_LIDAR_ENCAPSULATION_HH