wj_716_lidar_protocol.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532
  1. #include "wj_716_lidar_protocol.h"
  2. #include <iostream>
  3. namespace wj_lidar
  4. {
  5. /**
  6. * 扫描点云转换为欧式坐标,并根据标定参数进行坐标变换
  7. * */
  8. Error_manager scan_transform(wj::wjLidarParams params, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out)
  9. {
  10. // 1. 合法性检验
  11. if (!params.has_net_config() || !params.has_transform() || !params.has_scan_limit())
  12. {
  13. LOG(WARNING) << "网络参数 " << params.has_net_config() << ", 坐标变换参数: " << params.has_transform() << ", 范围限制: " << params.has_scan_limit();
  14. return Error_manager(Error_code::PARAMETER_ERROR);
  15. }
  16. // 2. 将极坐标转换为欧式坐标,其中原极坐标r存于点云x坐标中,原极坐标theta通过角度最小值与角分辨率计算
  17. float angle = params.angle_min();
  18. cloud_out->clear();
  19. // LOG(INFO) << "cloud size before transform: " <<cloud_in->size();
  20. for (size_t i = 0; i < cloud_in->size(); ++i)
  21. {
  22. const float first_echo = cloud_in->points[i].x;
  23. // within the border
  24. if (params.range_min() <= first_echo && first_echo <= params.range_max() && first_echo <= params.scan_limit().dist_limit())
  25. {
  26. const Eigen::AngleAxisf rotation(angle, Eigen::Vector3f::UnitZ());
  27. Eigen::MatrixXf mat = rotation * (first_echo * Eigen::Vector3f::UnitX());
  28. /*Eigen::Matrix<float,4,1> e_transform;
  29. e_transform<<mat,1.0;
  30. Eigen::MatrixXf new_pos=tf_btol*e_transform;*/
  31. float x = mat(0, 0);
  32. float y = mat(1, 0);
  33. if (x < params.scan_limit().minx() || x > params.scan_limit().maxx() || y < params.scan_limit().miny() || y > params.scan_limit().maxy())
  34. {
  35. angle += params.angle_increment();
  36. continue;
  37. }
  38. float newx = x * params.transform().m00() + y * params.transform().m01() + params.transform().m02();
  39. float newy = x * params.transform().m10() + y * params.transform().m11() + params.transform().m12();
  40. pcl::PointXYZ point(newx, newy, 0);
  41. cloud_out->push_back(point);
  42. // cloud_in->points[i].x = newx;
  43. // cloud_in->points[i].y = newy;
  44. }
  45. angle += params.angle_increment();
  46. }
  47. return Error_manager(Error_code::SUCCESS);
  48. }
  49. /**
  50. * 设置参数
  51. * */
  52. void Wj_716_lidar_protocol::set_config(wj::wjLidarParams &params)
  53. {
  54. // m_lidar_params.CopyFrom(params);
  55. m_lidar_params.set_angle_min(params.angle_min());
  56. m_lidar_params.set_angle_max(params.angle_max());
  57. m_lidar_params.set_angle_increment(params.angle_increment());
  58. m_lidar_params.set_range_min(params.range_min());
  59. m_lidar_params.set_range_max(params.range_max());
  60. m_lidar_params.set_range_min(params.range_min());
  61. m_lidar_params.mutable_net_config()->set_ip_address(params.net_config().ip_address());
  62. m_lidar_params.mutable_net_config()->set_port(params.net_config().port());
  63. m_lidar_params.mutable_scan_limit()->set_maxx(params.scan_limit().maxx());
  64. m_lidar_params.mutable_scan_limit()->set_minx(params.scan_limit().minx());
  65. m_lidar_params.mutable_scan_limit()->set_maxy(params.scan_limit().maxy());
  66. m_lidar_params.mutable_scan_limit()->set_miny(params.scan_limit().miny());
  67. m_lidar_params.mutable_scan_limit()->set_dist_limit(params.scan_limit().dist_limit());
  68. m_lidar_params.mutable_transform()->set_m00(params.transform().m00());
  69. m_lidar_params.mutable_transform()->set_m01(params.transform().m01());
  70. m_lidar_params.mutable_transform()->set_m02(params.transform().m02());
  71. m_lidar_params.mutable_transform()->set_m10(params.transform().m10());
  72. m_lidar_params.mutable_transform()->set_m11(params.transform().m11());
  73. m_lidar_params.mutable_transform()->set_m12(params.transform().m12());
  74. LOG(INFO) << "\n" << m_lidar_params.DebugString();
  75. // LOG(INFO) << "min_ang:" << m_lidar_params.angle_min();
  76. // LOG(INFO) << "max_ang:" << m_lidar_params.angle_max();
  77. // LOG(INFO) << "angle_increment:" << m_lidar_params.angle_increment();
  78. // LOG(INFO) << "time_increment:" << m_lidar_params.time_increment();
  79. // LOG(INFO) << "range_min:" << m_lidar_params.range_min();
  80. // LOG(INFO) << "range_max:" << m_lidar_params.range_max();
  81. }
  82. /**
  83. * 获取更新扫描点云时间
  84. * */
  85. std::chrono::steady_clock::time_point Wj_716_lidar_protocol::get_scan_time()
  86. {
  87. return m_scan_cloud_time;
  88. }
  89. /**
  90. * 获取更新二次回波时间
  91. * */
  92. std::chrono::steady_clock::time_point Wj_716_lidar_protocol::get_two_echo_time()
  93. {
  94. return m_two_echo_cloud_time;
  95. }
  96. /**
  97. * 获取扫描点云
  98. * */
  99. Error_manager Wj_716_lidar_protocol::get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out)
  100. {
  101. Error_manager result;
  102. m_scan_mutex.lock();
  103. result = scan_transform(m_lidar_params, mp_scan_points, cloud_out);
  104. m_scan_mutex.unlock();
  105. if (result != SUCCESS)
  106. {
  107. LOG(WARNING) << "获取点云失败,参数错误";
  108. }
  109. return result;
  110. }
  111. /**
  112. * 获取二次回波点云
  113. * */
  114. Error_manager Wj_716_lidar_protocol::get_two_echo_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out)
  115. {
  116. Error_manager result;
  117. m_two_echo_mutex.lock();
  118. result = scan_transform(m_lidar_params, mp_two_echo_points, cloud_out);
  119. m_two_echo_mutex.unlock();
  120. if (result != SUCCESS)
  121. {
  122. LOG(WARNING) << "获取点云失败,参数错误";
  123. }
  124. return result;
  125. }
  126. /**
  127. * 万集协议栈初始化
  128. * */
  129. Error_manager Wj_716_lidar_protocol::initialize(wj::wjLidarParams params)
  130. {
  131. memset(&m_sdata, 0, sizeof(m_sdata));
  132. memset(m_scandata, 0, 811);
  133. memset(m_scandata_te, 0, 811);
  134. memset(scaninden, 0, 811);
  135. m_g_u32PreFrameNo = 0;
  136. mp_scan_points = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  137. mp_two_echo_points = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  138. mp_scan_points->resize(811);
  139. mp_two_echo_points->resize(811);
  140. m_lidar_params.set_angle_min(-2.35619449);
  141. m_lidar_params.set_angle_max(2.35619449);
  142. m_lidar_params.set_angle_increment(0.00582);
  143. m_lidar_params.set_time_increment(0.0667 / 1081);
  144. m_lidar_params.set_range_min(0);
  145. m_lidar_params.set_range_max(30);
  146. // 设置初始时间为昨天,以避免第一次点云更新前获取到空点云
  147. m_scan_cloud_time = std::chrono::steady_clock::now() - std::chrono::duration<int, std::ratio<60 * 60 * 24>>(1);
  148. m_two_echo_cloud_time = std::chrono::steady_clock::now() - std::chrono::duration<int, std::ratio<60 * 60 * 24>>(1);
  149. set_config(params);
  150. LOG(INFO) << "wj_716_lidar_protocol start successfully";
  151. mb_initialized = true;
  152. return Error_manager(Error_code::SUCCESS);
  153. }
  154. Wj_716_lidar_protocol::Wj_716_lidar_protocol():
  155. mb_initialized(0),
  156. s_n32ScanIndex(0)
  157. {
  158. }
  159. Wj_716_lidar_protocol::~Wj_716_lidar_protocol()
  160. {
  161. LOG(INFO) << "protocol destructed";
  162. }
  163. /**
  164. * 数据处理主函数
  165. **/
  166. Error_manager Wj_716_lidar_protocol::data_process(const char *data, const int reclen)
  167. {
  168. // 1. 判断长度合法性
  169. if (reclen > MAX_LENGTH_DATA_PROCESS)
  170. {
  171. return Error_manager(Error_code::WJ_PROTOCOL_EXCEED_MAX_SIZE);
  172. }
  173. if (m_sdata.m_u32in + reclen > MAX_LENGTH_DATA_PROCESS)
  174. {
  175. memset(&m_sdata, 0, sizeof(m_sdata));
  176. return Error_manager(Error_code::WJ_PROTOCOL_EXCEED_MAX_SIZE);
  177. }
  178. memcpy(&m_sdata.m_acdata[m_sdata.m_u32in], data, reclen * sizeof(char));
  179. m_sdata.m_u32in += reclen;
  180. // 2. 数据处理
  181. while (m_sdata.m_u32out < m_sdata.m_u32in)
  182. {
  183. // LOG(INFO) << "in: " << m_sdata.m_u32in << " out: " << m_sdata.m_u32out;
  184. if (m_sdata.m_acdata[m_sdata.m_u32out] == 0x02 && m_sdata.m_acdata[m_sdata.m_u32out + 1] == 0x02 &&
  185. m_sdata.m_acdata[m_sdata.m_u32out + 2] == 0x02 && m_sdata.m_acdata[m_sdata.m_u32out + 3] == 0x02)
  186. {
  187. unsigned l_u32reallen = (m_sdata.m_acdata[m_sdata.m_u32out + 4] << 24) |
  188. (m_sdata.m_acdata[m_sdata.m_u32out + 5] << 16) |
  189. (m_sdata.m_acdata[m_sdata.m_u32out + 6] << 8) |
  190. (m_sdata.m_acdata[m_sdata.m_u32out + 7] << 0);
  191. l_u32reallen = l_u32reallen + 9;
  192. if (l_u32reallen <= (m_sdata.m_u32in - m_sdata.m_u32out + 1))
  193. {
  194. Error_manager code = on_recv_process(&m_sdata.m_acdata[m_sdata.m_u32out], l_u32reallen);
  195. // LOG(INFO) << "in: " << m_sdata.m_u32in << " out: " << m_sdata.m_u32out << " frame size: " << l_u32reallen;
  196. if (code == SUCCESS)
  197. {
  198. m_sdata.m_u32out = m_sdata.m_u32out + l_u32reallen;
  199. }
  200. else
  201. {
  202. LOG(INFO) << "continuous frame" << l_u32reallen;
  203. int i;
  204. for (i == 1; i < l_u32reallen; i++)
  205. {
  206. if ((m_sdata.m_acdata[m_sdata.m_u32out + i] == 0x02) &&
  207. (m_sdata.m_acdata[m_sdata.m_u32out + i + 1] == 0x02) &&
  208. (m_sdata.m_acdata[m_sdata.m_u32out + i + 2] == 0x02) &&
  209. (m_sdata.m_acdata[m_sdata.m_u32out + i + 3] == 0x02))
  210. {
  211. m_sdata.m_u32out += i;
  212. break;
  213. }
  214. if (i == l_u32reallen)
  215. {
  216. m_sdata.m_u32out += l_u32reallen;
  217. }
  218. }
  219. }
  220. }
  221. else if (l_u32reallen >= MAX_LENGTH_DATA_PROCESS)
  222. {
  223. LOG(INFO) << "l_u32reallen >= MAX_LENGTH_DATA_PROCESS";
  224. LOG(INFO) << "reallen: " << l_u32reallen;
  225. memset(&m_sdata, 0, sizeof(m_sdata));
  226. }
  227. else
  228. {
  229. LOG(INFO)<<"reallen: "<<l_u32reallen<<" indata: "<<m_sdata.m_u32in<<" outdata: "<<m_sdata.m_u32out;
  230. break;
  231. }
  232. }
  233. else
  234. {
  235. m_sdata.m_u32out++;
  236. }
  237. } //end while(m_sdata.m_u32out < m_sdata.m_u32in)
  238. if (m_sdata.m_u32out >= m_sdata.m_u32in)
  239. {
  240. memset(&m_sdata, 0, sizeof(m_sdata));
  241. }
  242. return Error_manager(Error_code::SUCCESS);
  243. }
  244. /**
  245. * 获取消息处理, 判断参数合法性,完整性检验并调用协议栈解析
  246. * */
  247. Error_manager Wj_716_lidar_protocol::on_recv_process(char *data, int len)
  248. {
  249. if (len > 0)
  250. {
  251. Error_manager code = check_xor(data, len);
  252. if (code == SUCCESS)
  253. {
  254. code = protocol(data, len);
  255. if (code != SUCCESS)
  256. {
  257. LOG(WARNING) << "万集雷达协议解析失败";
  258. }
  259. }
  260. else
  261. {
  262. LOG(WARNING) << "万集雷达信息完整性验证失败";
  263. }
  264. }
  265. else
  266. {
  267. return Error_manager(Error_code::WJ_PROTOCOL_EMPTY_PACKAGE);
  268. }
  269. return Error_manager(Error_code::SUCCESS);
  270. }
  271. /**
  272. * 协议栈解析
  273. * */
  274. Error_manager Wj_716_lidar_protocol::protocol(const char *data, const int len)
  275. {
  276. // LOG(INFO) << "command type " << data[8] << data[9] << " package number: " << (data[50] << 8) + data[51];
  277. if ((data[8] == 0x73 && data[9] == 0x52) || (data[8] == 0x73 && data[9] == 0x53)) //command type:0x73(s) 0x52/0X53(R/S)
  278. {
  279. // static int s_n32ScanIndex;
  280. int l_n32PackageNo = (data[50] << 8) + data[51]; //shuju bao xu hao
  281. unsigned int l_u32FrameNo = (data[46] << 24) + (data[47] << 16) + (data[48] << 8) + data[49]; //quan hao
  282. if (l_n32PackageNo == 1)
  283. {
  284. s_n32ScanIndex = 0;
  285. m_g_u32PreFrameNo = l_u32FrameNo;
  286. for (int j = 0; j < 810; j = j + 2)
  287. {
  288. m_scandata[s_n32ScanIndex] = (((unsigned char)data[85 + j]) << 8) + ((unsigned char)data[86 + j]);
  289. m_scandata[s_n32ScanIndex] /= 1000.0;
  290. if (m_scandata[s_n32ScanIndex] >= 25 || m_scandata[s_n32ScanIndex] == 0)
  291. {
  292. m_scandata[s_n32ScanIndex] = NAN;
  293. }
  294. s_n32ScanIndex++;
  295. }
  296. //cout << "quan hao1: " << g_u32PreFrameNo << " danzhen quanhao1: " << l_u32FrameNo<< endl;
  297. }
  298. else if (l_n32PackageNo == 2)
  299. {
  300. if (m_g_u32PreFrameNo == l_u32FrameNo)
  301. {
  302. m_scan_mutex.lock();
  303. // m_scan_points.clear();
  304. for (int j = 0; j < 812; j = j + 2)
  305. {
  306. m_scandata[s_n32ScanIndex] = (((unsigned char)data[85 + j]) << 8) + ((unsigned char)data[86 + j]);
  307. m_scandata[s_n32ScanIndex] /= 1000.0;
  308. if (m_scandata[s_n32ScanIndex] >= 25 || m_scandata[s_n32ScanIndex] == 0)
  309. {
  310. m_scandata[s_n32ScanIndex] = NAN;
  311. }
  312. // m_scan_points[s_n32ScanIndex].intensity = 0;
  313. // scan.intensities[s_n32ScanIndex] = 0;
  314. s_n32ScanIndex++;
  315. }
  316. m_scan_mutex.unlock();
  317. }
  318. else
  319. {
  320. s_n32ScanIndex = 0;
  321. //cout << "quan hao2: " << g_u32PreFrameNo << " danzhen quanhao2: " << l_u32FrameNo<< endl;
  322. return Error_manager(Error_code::WJ_PROTOCOL_PARSE_FAILED);
  323. }
  324. }
  325. else if (l_n32PackageNo == 3)
  326. {
  327. s_n32ScanIndex = 0;
  328. if (m_g_u32PreFrameNo == l_u32FrameNo)
  329. {
  330. for (int j = 0; j < 810; j = j + 2)
  331. {
  332. scaninden[s_n32ScanIndex] = (((unsigned char)data[85 + j]) << 8) + ((unsigned char)data[86 + j]);
  333. s_n32ScanIndex++;
  334. }
  335. }
  336. else
  337. {
  338. s_n32ScanIndex = 0;
  339. //cout << "quan hao3: " << g_u32PreFrameNo << " danzhen quanhao3: " << l_u32FrameNo<< endl;
  340. return Error_manager(Error_code::WJ_PROTOCOL_PARSE_FAILED);
  341. }
  342. }
  343. else if (l_n32PackageNo == 4)
  344. {
  345. if (m_g_u32PreFrameNo == l_u32FrameNo)
  346. {
  347. for (int j = 0; j < 812; j = j + 2)
  348. {
  349. scaninden[s_n32ScanIndex] = (((unsigned char)data[85 + j]) << 8) + ((unsigned char)data[86 + j]);
  350. s_n32ScanIndex++;
  351. }
  352. // adjust angle_min to min_ang config param
  353. int index_min = (m_lidar_params.angle_min() + 2.35619449) / m_lidar_params.angle_increment();
  354. // adjust angle_max to max_ang config param
  355. int index_max = 811 - ((2.35619449 - m_lidar_params.angle_max()) / m_lidar_params.angle_increment());
  356. m_scan_mutex.lock();
  357. mp_scan_points->clear();
  358. // mp_scan_points->resize(index_max - index_min);
  359. // scan.ranges.resize(index_max-index_min);
  360. // scan.intensities.resize(index_max-index_min);
  361. for (int j = index_min; j <= index_max; ++j)
  362. {
  363. pcl::PointXYZ point;
  364. point.x = m_scandata[j];
  365. point.y = 0;
  366. point.z = 0;
  367. mp_scan_points->push_back(point);
  368. // mp_scan_points->points[j - index_min].x = m_scandata[j];
  369. // mp_scan_points->points[j - index_min].y = 0;
  370. // mp_scan_points->points[j - index_min].z = 0;
  371. // m_scan_points[j - index_min].intensity = scaninden[j];
  372. // scan.ranges[j - index_min] = scandata[j];
  373. // scan.intensities[j - index_min]=scaninden[j];
  374. }
  375. m_scan_mutex.unlock();
  376. m_scan_cloud_time = std::chrono::steady_clock::now();
  377. // LOG(INFO) << "protocol cloud size: " << mp_scan_points->size();
  378. }
  379. else
  380. {
  381. s_n32ScanIndex = 0;
  382. //cout << "quan hao4: " << g_u32PreFrameNo << " danzhen quanhao4: " << l_u32FrameNo<< endl;
  383. return Error_manager(Error_code::WJ_PROTOCOL_PARSE_FAILED);
  384. }
  385. }
  386. else if (l_n32PackageNo == 5)
  387. {
  388. s_n32ScanIndex = 0;
  389. if (m_g_u32PreFrameNo == l_u32FrameNo)
  390. {
  391. for (int j = 0; j < 810; j = j + 2)
  392. {
  393. m_scandata_te[s_n32ScanIndex] = (((unsigned char)data[85 + j]) << 8) + ((unsigned char)data[86 + j]);
  394. m_scandata_te[s_n32ScanIndex] /= 1000.0;
  395. if (m_scandata_te[s_n32ScanIndex] >= 55 || m_scandata_te[s_n32ScanIndex] == 0)
  396. {
  397. m_scandata_te[s_n32ScanIndex] = NAN;
  398. }
  399. s_n32ScanIndex++;
  400. }
  401. }
  402. else
  403. {
  404. s_n32ScanIndex = 0;
  405. //cout << "quan hao5: " << g_u32PreFrameNo << " danzhen quanhao5: " << l_u32FrameNo<< endl;
  406. return Error_manager(Error_code::WJ_PROTOCOL_PARSE_FAILED);
  407. }
  408. }
  409. else if (l_n32PackageNo == 6)
  410. {
  411. if (m_g_u32PreFrameNo == l_u32FrameNo)
  412. {
  413. for (int j = 0; j < 812; j = j + 2)
  414. {
  415. m_scandata_te[s_n32ScanIndex] = (((unsigned char)data[85 + j]) << 8) + ((unsigned char)data[86 + j]);
  416. m_scandata_te[s_n32ScanIndex] /= 1000.0;
  417. if (m_scandata_te[s_n32ScanIndex] >= 55 || m_scandata_te[s_n32ScanIndex] == 0)
  418. {
  419. m_scandata_te[s_n32ScanIndex] = NAN;
  420. }
  421. s_n32ScanIndex++;
  422. }
  423. int index_min = (m_lidar_params.angle_min() + 2.35619449) / m_lidar_params.angle_increment();
  424. // adjust angle_max to max_ang config param
  425. int index_max = 811 - ((2.35619449 - m_lidar_params.angle_max()) / m_lidar_params.angle_increment());
  426. m_two_echo_mutex.lock();
  427. mp_two_echo_points->clear();
  428. // mp_two_echo_points->resize(index_max - index_min);
  429. // scan_TwoEcho.ranges.resize(index_max-index_min);
  430. // scan_TwoEcho.intensities.resize(index_max-index_min);
  431. for (int j = index_min; j <= index_max; ++j)
  432. {
  433. pcl::PointXYZ point;
  434. point.x = m_scandata_te[j];
  435. point.y = 0;
  436. point.z = 0;
  437. mp_two_echo_points->push_back(point);
  438. // mp_two_echo_points->points[j - index_min].x = m_scandata_te[j];
  439. // mp_two_echo_points->points[j - index_min].y = 0;
  440. // mp_two_echo_points->points[j - index_min].z = 0;
  441. // m_two_echo_points[j - index_min].intensity = 0;
  442. // scan_TwoEcho.ranges[j - index_min] = scandata_te[j];
  443. // scan_TwoEcho.intensities[j - index_min] =0;
  444. }
  445. m_two_echo_mutex.unlock();
  446. m_two_echo_cloud_time = std::chrono::steady_clock::now();
  447. }
  448. else
  449. {
  450. s_n32ScanIndex = 0;
  451. //cout << "quan hao6: " << g_u32PreFrameNo << " danzhen quanhao6: " << l_u32FrameNo<< endl;
  452. return Error_manager(Error_code::WJ_PROTOCOL_PARSE_FAILED);
  453. }
  454. }
  455. return Error_manager(Error_code::SUCCESS);
  456. }
  457. else
  458. {
  459. return Error_manager(Error_code::WJ_PROTOCOL_PARSE_FAILED);
  460. }
  461. }
  462. /**
  463. * 数据包完整性检查
  464. **/
  465. Error_manager Wj_716_lidar_protocol::check_xor(char *recvbuf, int recvlen)
  466. {
  467. int i = 0;
  468. char check = 0;
  469. char *p = recvbuf;
  470. int len;
  471. if (*p == (char)0x02)
  472. {
  473. p = p + 8;
  474. len = recvlen - 9;
  475. for (i = 0; i < len; i++)
  476. {
  477. check ^= *p++;
  478. }
  479. if (check == *p)
  480. {
  481. return Error_manager(Error_code::SUCCESS);
  482. }
  483. else
  484. return Error_manager(Error_code::WJ_PROTOCOL_INTEGRITY_ERROR);
  485. }
  486. else
  487. {
  488. return Error_manager(Error_code::WJ_PROTOCOL_INTEGRITY_ERROR);
  489. }
  490. }
  491. /**
  492. * 初始化状态获取
  493. * */
  494. bool Wj_716_lidar_protocol::get_initialize_status()
  495. {
  496. return mb_initialized;
  497. }
  498. } // namespace wj_lidar