wj_716N_lidar_protocol.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458
  1. #include "wj_716N_lidar_protocol.h"
  2. #include <iostream>
  3. wj_716N_lidar_protocol::wj_716N_lidar_protocol()
  4. {
  5. memset(&m_sdata, 0, sizeof(m_sdata));
  6. // marker_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 50);
  7. // ros::Time scan_time = ros::Time::now();
  8. // scan.header.stamp = scan_time;
  9. long scan_time=std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  10. scan.header.stamp.msecs = scan_time;
  11. mp_communication_data_queue = NULL;
  12. freq_scan = 1;
  13. m_u32PreFrameNo = 0;
  14. m_u32ExpectedPackageNo = 0;
  15. m_n32currentDataNo = 0;
  16. total_point = 1081;
  17. scan.header.frame_id = "wj_716N_lidar_frame";
  18. scan.angle_min = -2.35619449;
  19. scan.angle_max = 2.35619449;
  20. scan.angle_increment = 0.017453 / 4;
  21. scan.time_increment = 1 / 15.00000000 / 1440;
  22. scan.range_min = 0;
  23. scan.range_max = 30;
  24. scan.ranges.resize(1081);
  25. scan.intensities.resize(1081);
  26. scan.x.resize(1081);
  27. scan.y.resize(1081);
  28. scan.angle_to_point.resize(1081);
  29. index_start = (config_.min_ang + 2.35619449) / scan.angle_increment;
  30. // adjust angle_max to max_ang config param
  31. index_end = 1081 - ((2.35619449 - config_.max_ang) / scan.angle_increment);
  32. mp_scan_points = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  33. mp_thread_analysis = nullptr;
  34. std::cout << "wj_716N_lidar_protocl start success" << std::endl;
  35. }
  36. bool wj_716N_lidar_protocol::setConfig(wj_716_lidarConfig &new_config, uint32_t level)
  37. {
  38. config_ = new_config;
  39. scan.header.frame_id = config_.frame_id;
  40. scan.angle_min = config_.min_ang;
  41. scan.angle_max = config_.max_ang;
  42. scan.range_min = config_.range_min;
  43. scan.range_max = config_.range_max;
  44. freq_scan = config_.frequency_scan;
  45. scan.angle_increment = 0.017453 / 4;
  46. if (freq_scan == 1) //0.25°_15hz
  47. {
  48. scan.time_increment = 1 / 15.00000000 / 1440;
  49. total_point = 1081;
  50. }
  51. else if (freq_scan == 2) //0.25°_25hz
  52. {
  53. scan.time_increment = 1 / 25.00000000 / 1440;
  54. total_point = 1081;
  55. }
  56. // adjust angle_min to min_ang config param
  57. index_start = (config_.min_ang + 2.35619449) / scan.angle_increment;
  58. // adjust angle_max to max_ang config param
  59. index_end = 1081 - ((2.35619449 - config_.max_ang) / scan.angle_increment);
  60. int samples = index_end - index_start;
  61. // scan.ranges.resize(samples);
  62. // scan.intensities.resize(samples);
  63. std::cout << "frame_id:" << scan.header.frame_id << std::endl;
  64. std::cout << "min_ang:" << scan.angle_min << std::endl;
  65. std::cout << "max_ang:" << scan.angle_max << std::endl;
  66. std::cout << "angle_increment:" << scan.angle_increment << std::endl;
  67. std::cout << "time_increment:" << scan.time_increment << std::endl;
  68. std::cout << "range_min:" << scan.range_min << std::endl;
  69. std::cout << "range_max:" << scan.range_max << std::endl;
  70. std::cout << "samples_per_scan:" << samples << std::endl;
  71. return true;
  72. }
  73. // 初始化
  74. Error_manager wj_716N_lidar_protocol::init(Thread_safe_queue<Binary_buf *> *p_communication_data_queue,
  75. Point2D_tool::Polar_coordinates_box polar_coordinates_box,
  76. Point2D_tool::Point2D_box point2D_box,
  77. Point2D_tool::Point2D_transform point2D_transform)
  78. {
  79. if (p_communication_data_queue == NULL)
  80. {
  81. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  82. " POINTER IS NULL ");
  83. }
  84. wj_716_lidarConfig t_config;
  85. t_config.min_ang = polar_coordinates_box.angle_min;
  86. t_config.max_ang = polar_coordinates_box.angle_max;
  87. t_config.range_min = polar_coordinates_box.distance_min;
  88. t_config.range_max = polar_coordinates_box.distance_max;
  89. setConfig(t_config, 0);
  90. mp_communication_data_queue = p_communication_data_queue;
  91. m_point2D_box = point2D_box;
  92. m_point2D_transform = point2D_transform;
  93. //接受线程, 默认开启循环, 在内部的wait_and_pop进行等待
  94. m_condition_analysis.reset(false, true, false);
  95. mp_thread_analysis = new std::thread(&wj_716N_lidar_protocol::thread_analysis, this);
  96. return Error_code::SUCCESS;
  97. }
  98. //反初始化
  99. Error_manager wj_716N_lidar_protocol::uninit()
  100. {
  101. LOG(INFO) << " ---wj_716N_lidar_protocol uninit --- "<< this;
  102. if ( mp_communication_data_queue )
  103. {
  104. //终止队列,防止 wait_and_pop 阻塞线程。
  105. mp_communication_data_queue->termination_queue();
  106. }
  107. //关闭线程
  108. if (mp_thread_analysis)
  109. {
  110. m_condition_analysis.kill_all();
  111. }
  112. //回收线程的资源
  113. if (mp_thread_analysis)
  114. {
  115. mp_thread_analysis->join();
  116. delete mp_thread_analysis;
  117. mp_thread_analysis = NULL;
  118. }
  119. if ( mp_communication_data_queue )
  120. {
  121. //清空队列
  122. mp_communication_data_queue->clear_and_delete();
  123. }
  124. //队列的内存由上级管理, 这里写空就好了.
  125. mp_communication_data_queue = NULL;
  126. return Error_code::SUCCESS;
  127. }
  128. //获取扫描点云
  129. Error_manager wj_716N_lidar_protocol::get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_out)
  130. {
  131. if ( p_cloud_out.get() == NULL )
  132. {
  133. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  134. " Wj_716_lidar_protocol::get_scan_points POINTER IS NULL ");
  135. }
  136. std::unique_lock<std::mutex> lck(m_scan_mutex);
  137. //将扫描点云追加到p_cloud_out后面, 不要清除p_cloud_out原有的数据
  138. (*p_cloud_out)+=(*mp_scan_points);
  139. return Error_code::SUCCESS;
  140. }
  141. //解析线程函数
  142. void wj_716N_lidar_protocol::thread_analysis()
  143. {
  144. LOG(INFO) << " ---Wj_716_lidar_protocol::thread_analysis start ---" << this;
  145. Error_manager t_error;
  146. //接受雷达消息,包括连接,重连和接受数据
  147. while (m_condition_analysis.is_alive())
  148. {
  149. m_condition_analysis.wait();
  150. if (m_condition_analysis.is_alive())
  151. {
  152. std::this_thread::yield();
  153. if (mp_communication_data_queue == NULL)
  154. {
  155. // m_wanji_lidar_protocol_status = E_FAULT;
  156. }
  157. else
  158. {
  159. Binary_buf *tp_binary_buf = NULL;
  160. bool is_pop = mp_communication_data_queue->wait_and_pop(tp_binary_buf);
  161. if (is_pop == true && tp_binary_buf != NULL)
  162. {
  163. if(dataProcess((unsigned char *)tp_binary_buf->get_buf(), tp_binary_buf->get_length()))
  164. {
  165. t_error = SUCCESS;
  166. }else{
  167. t_error = ERROR;
  168. }
  169. //else 错误不管, 当做无效消息处理
  170. delete(tp_binary_buf);
  171. }
  172. }
  173. }
  174. }
  175. LOG(INFO) << " -Wj_716_lidar_protocol::thread_analysis end :" << this;
  176. return;
  177. }
  178. bool wj_716N_lidar_protocol::dataProcess(unsigned char *data, const int reclen)
  179. {
  180. if (reclen > MAX_LENGTH_DATA_PROCESS)
  181. {
  182. m_sdata.m_u32out = 0;
  183. m_sdata.m_u32in = 0;
  184. return false;
  185. }
  186. if (m_sdata.m_u32in + reclen > MAX_LENGTH_DATA_PROCESS)
  187. {
  188. m_sdata.m_u32out = 0;
  189. m_sdata.m_u32in = 0;
  190. return false;
  191. }
  192. memcpy(&m_sdata.m_acdata[m_sdata.m_u32in], data, reclen * sizeof(char));
  193. m_sdata.m_u32in += reclen;
  194. while (m_sdata.m_u32out < m_sdata.m_u32in)
  195. {
  196. if (m_sdata.m_acdata[m_sdata.m_u32out] == 0xFF && m_sdata.m_acdata[m_sdata.m_u32out + 1] == 0xAA)
  197. {
  198. unsigned l_u32reallen = (m_sdata.m_acdata[m_sdata.m_u32out + 2] << 8) |
  199. (m_sdata.m_acdata[m_sdata.m_u32out + 3] << 0);
  200. l_u32reallen = l_u32reallen + 4;
  201. if (l_u32reallen <= (m_sdata.m_u32in - m_sdata.m_u32out + 1))
  202. {
  203. if (OnRecvProcess(&m_sdata.m_acdata[m_sdata.m_u32out], l_u32reallen))
  204. {
  205. m_sdata.m_u32out += l_u32reallen;
  206. }
  207. else
  208. {
  209. std::cout << "continuous search frame header" << std::endl;
  210. m_sdata.m_u32out++;
  211. }
  212. }
  213. else if (l_u32reallen >= MAX_LENGTH_DATA_PROCESS)
  214. {
  215. m_sdata.m_u32out++;
  216. }
  217. else
  218. {
  219. break;
  220. }
  221. }
  222. else
  223. {
  224. m_sdata.m_u32out++;
  225. }
  226. } //end while(m_sdata.m_u32out < m_sdata.m_u32in)
  227. if (m_sdata.m_u32out >= m_sdata.m_u32in)
  228. {
  229. m_sdata.m_u32out = 0;
  230. m_sdata.m_u32in = 0;
  231. }
  232. else if (m_sdata.m_u32out < m_sdata.m_u32in && m_sdata.m_u32out != 0)
  233. {
  234. movedata(m_sdata);
  235. }
  236. return true;
  237. }
  238. void wj_716N_lidar_protocol::movedata(DataCache &sdata)
  239. {
  240. for (int i = sdata.m_u32out; i < sdata.m_u32in; i++)
  241. {
  242. sdata.m_acdata[i - sdata.m_u32out] = sdata.m_acdata[i];
  243. }
  244. sdata.m_u32in = sdata.m_u32in - sdata.m_u32out;
  245. sdata.m_u32out = 0;
  246. }
  247. bool wj_716N_lidar_protocol::OnRecvProcess(unsigned char *data, int len)
  248. {
  249. if (len > 0)
  250. {
  251. if (checkXor(data, len))
  252. {
  253. protocl(data, len);
  254. }
  255. else
  256. {
  257. return false;
  258. }
  259. }
  260. else
  261. {
  262. return false;
  263. }
  264. return true;
  265. }
  266. bool wj_716N_lidar_protocol::protocl(unsigned char *data, const int len)
  267. {
  268. if ((data[22] == 0x02 && data[23] == 0x02) || (data[22] == 0x02 && data[23] == 0x01)) //command type:0x02 0x01/0X02
  269. {
  270. heartstate = true;
  271. int l_n32TotalPackage = data[80];
  272. int l_n32PackageNo = data[81];
  273. unsigned int l_u32FrameNo = (data[75] << 24) + (data[76] << 16) + (data[77] << 8) + data[78];
  274. int l_n32PointNum = (data[83] << 8) + data[84];
  275. int l_n32Frequency = data[79];
  276. if(l_n32Frequency != freq_scan)
  277. {
  278. std::cout << "The scan frequency does not match the one you setted!"<< std::endl;
  279. return false;
  280. }
  281. if(m_u32PreFrameNo != l_u32FrameNo)
  282. {
  283. m_u32PreFrameNo = l_u32FrameNo;
  284. m_u32ExpectedPackageNo = 1;
  285. m_n32currentDataNo = 0;
  286. }
  287. if (l_n32PackageNo == m_u32ExpectedPackageNo && m_u32PreFrameNo == l_u32FrameNo)
  288. {
  289. if(data[82] == 0x00) //Dist
  290. {
  291. for (int j = 0; j < l_n32PointNum; j++)
  292. {
  293. scandata[m_n32currentDataNo] = (((unsigned char)data[85 + j * 2]) << 8) +
  294. ((unsigned char)data[86 + j * 2]);
  295. scandata[m_n32currentDataNo] /= 1000.0;
  296. scanintensity[m_n32currentDataNo] = 0;
  297. if (scandata[m_n32currentDataNo] > scan.range_max || scandata[m_n32currentDataNo] < scan.range_min || scandata[m_n32currentDataNo] == 0)
  298. {
  299. scandata[m_n32currentDataNo] = NAN;
  300. }
  301. m_n32currentDataNo++;
  302. }
  303. m_u32ExpectedPackageNo++;
  304. }
  305. else if(data[82] == 0x01 && m_n32currentDataNo >= total_point) //intensities
  306. {
  307. for (int j = 0; j < l_n32PointNum; j++)
  308. {
  309. scanintensity[m_n32currentDataNo - total_point] = (((unsigned char)data[85 + j * 2]) << 8) +
  310. ((unsigned char)data[86 + j * 2]);
  311. m_n32currentDataNo++;
  312. }
  313. m_u32ExpectedPackageNo++;
  314. }
  315. if(m_u32ExpectedPackageNo - 1 == l_n32TotalPackage)
  316. {
  317. m_read_write_mtx.lock();
  318. mp_scan_points->clear();
  319. for (int i = index_start; i < index_end; i++)
  320. {
  321. scan.ranges[i - index_start] = scandata[i];
  322. //std::cout<<scan.ranges[i - index_start]<<std::endl;
  323. update_data(i-index_start);
  324. if(scandata[i - index_start] == NAN)
  325. {
  326. scan.intensities[i - index_start] = 0;
  327. }
  328. else
  329. {
  330. scan.intensities[i - index_start] = scanintensity[i];
  331. }
  332. pcl::PointXYZ point;
  333. //判断平面坐标点是否在限制范围
  334. double x = scan.x[i-index_start];
  335. double y = scan.y[i-index_start];
  336. if (Point2D_tool::limit_with_point2D_box(x, y, &m_point2D_box))
  337. {
  338. //平面坐标的转换, 可以进行旋转和平移, 不能缩放
  339. point.x = x * m_point2D_transform.m00 + y * m_point2D_transform.m01 + m_point2D_transform.m02;
  340. point.y = x * m_point2D_transform.m10 + y * m_point2D_transform.m11 + m_point2D_transform.m12;
  341. //添加到最终点云
  342. mp_scan_points->push_back(point);
  343. }
  344. }
  345. scan.header.stamp.msecs=std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  346. m_read_write_mtx.unlock();
  347. // ros::Time scan_time = ros::Time::now();
  348. // scan.header.stamp = scan_time;
  349. // marker_pub.publish(scan);
  350. }
  351. }
  352. return true;
  353. }
  354. else
  355. {
  356. return false;
  357. }
  358. }
  359. //index点数组下标【0~l_n32PointCount-1】 l_n32PointCount总点数
  360. void wj_716N_lidar_protocol::update_data(int index)
  361. {
  362. if(index>=total_point)
  363. {
  364. return;
  365. }
  366. // std::cout<<"该圈的数据总条数:"<<total_point_number_per_circle<<std::endl;
  367. // std::cout<<"数据点对应的数组下标:"<<index<<std::endl;
  368. // 每个下标对应的弧度
  369. scan.angle_to_point[index] = scan.angle_min+(total_point-1-index)*(scan.angle_max-scan.angle_min)/(total_point-1);
  370. scan.y[index]=scan.ranges[index]*cos(scan.angle_min+(total_point-1-index)*(scan.angle_max-scan.angle_min)/(total_point-1));
  371. scan.x[index]=scan.ranges[index]*sin(scan.angle_min+(total_point-1-index)*(scan.angle_max-scan.angle_min)/(total_point-1));
  372. // scan.angle_to_point[total_point-1-index] = scan.angle_min+(total_point-1-index)*(scan.angle_max-scan.angle_min)/(total_point-1);
  373. // scan.y[total_point-1-index]=scan.ranges[index]*cos(scan.angle_min+(total_point-1-index)*(scan.angle_max-scan.angle_min)/(total_point-1));
  374. // scan.x[total_point-1-index]=scan.ranges[index]*sin(scan.angle_min+(total_point-1-index)*(scan.angle_max-scan.angle_min)/(total_point-1));
  375. // if(index!=540)
  376. // std::cout<<"每个点对应的弧度: "<<scan.angle_to_point[total_point-1-index]<<", 每个点对应的距离: "<<scan.ranges[total_point-1-index]<<", (x,y): ("<<scan.x[total_point-1-index]<<","<<scan.y[total_point-1-index]<<")"<<std::endl;
  377. }
  378. bool wj_716N_lidar_protocol::checkXor(unsigned char *recvbuf, int recvlen)
  379. {
  380. int i = 0;
  381. unsigned char check = 0;
  382. unsigned char *p = recvbuf;
  383. int len;
  384. if (*p == 0xFF)
  385. {
  386. p = p + 2;
  387. len = recvlen - 6;
  388. for (i = 0; i < len; i++)
  389. {
  390. check ^= *p++;
  391. }
  392. p++;
  393. if (check == *p)
  394. {
  395. return true;
  396. }
  397. else
  398. return false;
  399. }
  400. else
  401. {
  402. return false;
  403. }
  404. }