wj_716N_lidar_protocol.cpp 14 KB

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