wj_716_lidar_protocol.cpp 19 KB

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