wj_716_lidar_protocol.h 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  1. #ifndef WJ_716_LIDAR_PROTOCOL_H
  2. #define WJ_716_LIDAR_PROTOCOL_H
  3. #include <iostream>
  4. #include "string.h"
  5. #include <boost/shared_ptr.hpp>
  6. #include <boost/asio.hpp>
  7. #include <boost/asio/placeholders.hpp>
  8. #include <boost/system/error_code.hpp>
  9. #include <boost/bind/bind.hpp>
  10. #include <mutex>
  11. #include <chrono>
  12. #include <pcl/point_types.h>
  13. #include <pcl/PCLPointCloud2.h>
  14. #include <pcl/conversions.h>
  15. #include <pcl/common/common.h>
  16. #include <google/protobuf/io/coded_stream.h>
  17. #include <google/protobuf/io/zero_copy_stream_impl.h>
  18. #include <google/protobuf/text_format.h>
  19. using google::protobuf::Message;
  20. using google::protobuf::io::CodedInputStream;
  21. using google::protobuf::io::CodedOutputStream;
  22. using google::protobuf::io::FileInputStream;
  23. using google::protobuf::io::FileOutputStream;
  24. using google::protobuf::io::ZeroCopyInputStream;
  25. using google::protobuf::io::ZeroCopyOutputStream;
  26. #include "glog/logging.h"
  27. #include "wj_lidar_conf.pb.h"
  28. #include "../error_code/error_code.h"
  29. // using namespace std ;
  30. namespace wj_lidar
  31. {
  32. #define MAX_LENGTH_DATA_PROCESS 200000
  33. typedef struct tag_data_cache
  34. {
  35. char m_acdata[MAX_LENGTH_DATA_PROCESS];
  36. unsigned int m_u32in;
  37. unsigned int m_u32out;
  38. } data_cache;
  39. class Wj_716_lidar_protocol
  40. {
  41. public:
  42. // 构造
  43. Wj_716_lidar_protocol();
  44. // 析构
  45. ~Wj_716_lidar_protocol();
  46. // 初始化
  47. Error_manager initialize(wj::wjLidarParams params);
  48. // 数据处理
  49. Error_manager data_process(const char *data, const int reclen);
  50. // 万集通信协议
  51. Error_manager protocol(const char *data, const int len);
  52. // 接收消息
  53. Error_manager on_recv_process(char *data, int len);
  54. // 消息完整性检查
  55. Error_manager check_xor(char *recvbuf, int recvlen);
  56. // 获取初始化状态
  57. bool get_initialize_status();
  58. // 获取扫描点云
  59. Error_manager get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out);
  60. Error_manager get_two_echo_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out);
  61. // 获取扫描点云更新时间点
  62. std::chrono::steady_clock::time_point get_scan_time();
  63. std::chrono::steady_clock::time_point get_two_echo_time();
  64. private:
  65. // 设置参数
  66. void set_config(wj::wjLidarParams &params);
  67. private:
  68. bool mb_initialized; // 初始化状态flag
  69. // 万集雷达参数
  70. wj::wjLidarParams m_lidar_params;
  71. data_cache m_sdata;
  72. // 扫描获取点云
  73. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_scan_points;
  74. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_two_echo_points;
  75. // 点云获取互斥锁
  76. std::mutex m_scan_mutex;
  77. std::mutex m_two_echo_mutex;
  78. unsigned int m_g_u32PreFrameNo;
  79. float m_scandata[811];
  80. float m_scandata_te[811];
  81. float scaninden[811];
  82. // 当前扫描下标
  83. int s_n32ScanIndex;
  84. // 扫描点云更新时间点
  85. std::chrono::steady_clock::time_point m_scan_cloud_time;
  86. std::chrono::steady_clock::time_point m_two_echo_cloud_time;
  87. };
  88. } // namespace wj_lidar
  89. #endif // WJ_716_LIDAR_PROTOCOL_H