123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104 |
- #ifndef WJ_716_LIDAR_PROTOCOL_H
- #define WJ_716_LIDAR_PROTOCOL_H
- #include <iostream>
- #include "string.h"
- #include <boost/shared_ptr.hpp>
- #include <boost/asio.hpp>
- #include <boost/asio/placeholders.hpp>
- #include <boost/system/error_code.hpp>
- #include <boost/bind/bind.hpp>
- #include <mutex>
- #include <chrono>
- #include <pcl/point_types.h>
- #include <pcl/PCLPointCloud2.h>
- #include <pcl/conversions.h>
- #include <pcl/common/common.h>
- #include <google/protobuf/io/coded_stream.h>
- #include <google/protobuf/io/zero_copy_stream_impl.h>
- #include <google/protobuf/text_format.h>
- using google::protobuf::Message;
- using google::protobuf::io::CodedInputStream;
- using google::protobuf::io::CodedOutputStream;
- using google::protobuf::io::FileInputStream;
- using google::protobuf::io::FileOutputStream;
- using google::protobuf::io::ZeroCopyInputStream;
- using google::protobuf::io::ZeroCopyOutputStream;
- #include "glog/logging.h"
- #include "wj_lidar_conf.pb.h"
- #include "../error_code/error_code.h"
- // using namespace std ;
- namespace wj_lidar
- {
-
- #define MAX_LENGTH_DATA_PROCESS 200000
- typedef struct tag_data_cache
- {
- char m_acdata[MAX_LENGTH_DATA_PROCESS];
- unsigned int m_u32in;
- unsigned int m_u32out;
- } data_cache;
- class Wj_716_lidar_protocol
- {
- public:
- // 构造
- Wj_716_lidar_protocol();
- // 析构
- ~Wj_716_lidar_protocol();
- // 初始化
- Error_manager initialize(wj::wjLidarParams params);
- // 数据处理
- Error_manager data_process(const char *data, const int reclen);
- // 万集通信协议
- Error_manager protocol(const char *data, const int len);
- // 接收消息
- Error_manager on_recv_process(char *data, int len);
- // 消息完整性检查
- Error_manager check_xor(char *recvbuf, int recvlen);
- // 获取初始化状态
- bool get_initialize_status();
- // 获取扫描点云
- Error_manager get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out);
- Error_manager get_two_echo_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out);
- // 获取扫描点云更新时间点
- std::chrono::steady_clock::time_point get_scan_time();
- std::chrono::steady_clock::time_point get_two_echo_time();
- private:
- // 设置参数
- void set_config(wj::wjLidarParams ¶ms);
- private:
- bool mb_initialized; // 初始化状态flag
- // 万集雷达参数
- wj::wjLidarParams m_lidar_params;
- data_cache m_sdata;
- // 扫描获取点云
- pcl::PointCloud<pcl::PointXYZ>::Ptr mp_scan_points;
- pcl::PointCloud<pcl::PointXYZ>::Ptr mp_two_echo_points;
- // 点云获取互斥锁
- std::mutex m_scan_mutex;
- std::mutex m_two_echo_mutex;
- unsigned int m_g_u32PreFrameNo;
- float m_scandata[811];
- float m_scandata_te[811];
- float scaninden[811];
- // 当前扫描下标
- int s_n32ScanIndex;
- // 扫描点云更新时间点
- std::chrono::steady_clock::time_point m_scan_cloud_time;
- std::chrono::steady_clock::time_point m_two_echo_cloud_time;
- };
- } // namespace wj_lidar
- #endif // WJ_716_LIDAR_PROTOCOL_H
|