Laser.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560
  1. #include "Laser.h"
  2. #include <unistd.h>
  3. #include <sys/types.h>
  4. #include <sys/stat.h>
  5. #include <time.h>
  6. #include <stdint.h>
  7. #include <stdio.h>
  8. Laser_base::Laser_base(int laser_id, Laser_proto::laser_parameter laser_param)
  9. :m_laser_id(laser_id)
  10. ,m_laser_param(laser_param)
  11. ,m_laser_scan_flag(false)
  12. ,m_laser_statu(LASER_DISCONNECT)
  13. ,m_points_count(0)
  14. ,m_save_flag(false)
  15. {
  16. mp_thread_receive = NULL;
  17. mp_thread_transform = NULL;
  18. mp_thread_publish = NULL;
  19. init_laser_matrix();
  20. mp_laser_task = NULL;
  21. }
  22. Laser_base::~Laser_base()
  23. {
  24. disconnect_laser();
  25. close_save_path();
  26. }
  27. //雷达链接设备,为3个线程添加线程执行函数。
  28. Error_manager Laser_base::connect_laser()
  29. {
  30. LOG(INFO) << " ---Laser_base::connect_laser() run--- "<< this;
  31. //检查雷达状态
  32. if ( m_laser_statu != LASER_DISCONNECT )
  33. {
  34. return Error_manager(Error_code::LASER_STATUS_ERROR, Error_level::MINOR_ERROR,
  35. " Laser_base::connect_laser m_laser_statu != LASER_DISCONNECT ");
  36. }
  37. else
  38. {
  39. //清空队列
  40. m_queue_laser_data.clear_and_delete();
  41. //唤醒队列,
  42. m_queue_laser_data.wake_queue();
  43. //这里不建议用detach,而是应该在disconnect里面使用join
  44. //创建接受缓存的线程,不允许重复创建
  45. if (mp_thread_receive != NULL)
  46. {
  47. return Error_manager(Error_code::LASER_CONNECT_FAILED, Error_level::MINOR_ERROR,
  48. " mp_thread_receive is alive ");
  49. }
  50. else
  51. {
  52. //接受缓存的线程,线程存活,暂停运行
  53. m_condition_receive.reset(false, false, false);
  54. mp_thread_receive = new std::thread(&Laser_base::thread_receive, this);
  55. }
  56. //转化数据的线程,不允许重复创建
  57. if (mp_thread_transform != NULL)
  58. {
  59. return Error_manager(Error_code::LASER_CONNECT_FAILED, Error_level::MINOR_ERROR,
  60. " mp_thread_transform is alive ");
  61. }
  62. else
  63. {
  64. //转化数据的线程,线程存活,暂停运行
  65. m_condition_transform.reset(false, false, false);
  66. mp_thread_transform = new std::thread(&Laser_base::thread_transform, this);
  67. }
  68. //发布信息的线程,不允许重复创建
  69. if (mp_thread_publish != NULL)
  70. {
  71. return Error_manager(Error_code::LASER_CONNECT_FAILED, Error_level::MINOR_ERROR,
  72. " mp_thread_publish is alive ");
  73. }
  74. else
  75. {
  76. //发布信息的线程,线程存活,循环运行,
  77. //注:mp_thread_publish 需要线程持续不断的往上位机发送信息,不受任务的影响。
  78. m_condition_publish.reset(false, true, false);
  79. mp_thread_publish = new std::thread(&Laser_base::thread_publish, this);
  80. }
  81. m_laser_statu = LASER_READY;
  82. }
  83. return Error_code::SUCCESS;
  84. }
  85. //雷达断开链接,释放3个线程
  86. Error_manager Laser_base::disconnect_laser()
  87. {
  88. LOG(INFO) << " ---Laser_base::disconnect_laser() run--- "<< this;
  89. //终止队列,防止 wait_and_pop 阻塞线程。
  90. m_queue_laser_data.termination_queue();
  91. //杀死3个线程,强制退出
  92. if (mp_thread_receive)
  93. {
  94. m_condition_receive.kill_all();
  95. }
  96. if (mp_thread_transform)
  97. {
  98. m_condition_transform.kill_all();
  99. }
  100. if (mp_thread_publish)
  101. {
  102. m_condition_publish.kill_all();
  103. }
  104. //回收3个线程的资源
  105. if (mp_thread_receive)
  106. {
  107. mp_thread_receive->join();
  108. delete mp_thread_receive;
  109. mp_thread_receive = NULL;
  110. }
  111. if (mp_thread_transform)
  112. {
  113. mp_thread_transform->join();
  114. delete mp_thread_transform;
  115. mp_thread_transform = 0;
  116. }
  117. if (mp_thread_publish)
  118. {
  119. mp_thread_publish->join();
  120. delete mp_thread_publish;
  121. mp_thread_publish = NULL;
  122. }
  123. //清空队列
  124. m_queue_laser_data.clear_and_delete();
  125. if ( m_laser_statu != LASER_FAULT )
  126. {
  127. m_laser_statu = LASER_DISCONNECT;
  128. }
  129. return Error_code::SUCCESS;
  130. }
  131. //对外的接口函数,负责接受并处理任务单,
  132. //input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
  133. //注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
  134. Error_manager Laser_base::execute_task(Task_Base* p_laser_task)
  135. {
  136. LOG(INFO) << " --Laser_base::execute_task run--- "<< this;
  137. //检查指针
  138. if(p_laser_task == NULL)
  139. {
  140. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  141. "Laser_base::execute_task failed, POINTER_IS_NULL");
  142. }
  143. else
  144. {
  145. return Error_manager(Error_code::CLASS_BASE_FUNCTION_CANNOT_USE, Error_level::NEGLIGIBLE_ERROR,
  146. "Laser_base::execute_task cannot use");
  147. }
  148. }
  149. //检查雷达状态,是否正常运行
  150. Error_manager Laser_base::check_status()
  151. {
  152. if ( get_laser_statu() == LASER_READY )
  153. {
  154. return Error_code::SUCCESS;
  155. }
  156. else if ( get_laser_statu() == LASER_BUSY )
  157. {
  158. return Error_manager(Error_code::LASER_STATUS_BUSY, Error_level::MINOR_ERROR,
  159. " CLivoxLaser::check_status error ");
  160. }
  161. else
  162. {
  163. return Error_manager(Error_code::LASER_STATUS_ERROR, Error_level::MINOR_ERROR,
  164. " CLivoxLaser::check_status error ");
  165. }
  166. return Error_code::SUCCESS;
  167. }
  168. //雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
  169. Error_manager Laser_base::start_scan()
  170. {
  171. LOG(INFO) << " ---Laser_base::start_scan ---"<< this;
  172. if ( is_ready() )
  173. {
  174. //重置数据
  175. m_points_count=0;
  176. m_queue_laser_data.clear_and_delete();
  177. m_last_data.clear();
  178. //启动雷达扫描
  179. m_laser_scan_flag=true; //启动雷达扫描
  180. m_laser_statu = LASER_BUSY; //雷达状态 繁忙
  181. m_condition_receive.notify_all(true); //唤醒接受线程
  182. m_condition_transform.notify_all(true); //唤醒转化线程
  183. return Error_code::SUCCESS;
  184. }
  185. else
  186. {
  187. return Error_manager(Error_code::LASER_START_FAILED, Error_level::MINOR_ERROR,
  188. "Laser_base::start_scan() is not ready ");
  189. }
  190. }
  191. //雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
  192. Error_manager Laser_base::stop_scan()
  193. {
  194. if(m_laser_scan_flag )
  195. {
  196. LOG(INFO) << " ---Laser_base::stop_scan ---"<< this;
  197. //stop_scan 只是将 m_laser_scan_flag 改为 stop。
  198. //然后多线程内部判断 m_laser_scan_flag,然后自动停止线程
  199. m_laser_scan_flag=false;
  200. }
  201. return Error_code::SUCCESS;
  202. }
  203. //结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
  204. Error_manager Laser_base::end_task()
  205. {
  206. LOG(INFO) << " ---Laser_base::end_task ---"<< this;
  207. stop_scan();
  208. m_laser_scan_flag=false;
  209. m_condition_receive.notify_all(false);
  210. m_condition_transform.notify_all(false);
  211. m_points_count=0;
  212. m_queue_laser_data.clear_and_delete();
  213. m_last_data.clear();
  214. close_save_path();
  215. //在结束任务单时,将雷达任务状态改为 TASK_OVER 已结束
  216. if(mp_laser_task !=NULL)
  217. {
  218. //判断任务单的错误等级,
  219. if ( mp_laser_task->get_task_error_manager().get_error_level() < Error_level::MINOR_ERROR)
  220. {
  221. if ( m_laser_statu == LASER_BUSY )
  222. {
  223. //故障等级为 NORMAL NEGLIGIBLE_ERROR MINOR_ERROR,则恢复待机,可以接受下一次的任务单
  224. m_laser_statu = LASER_READY;
  225. }
  226. mp_laser_task->set_task_statu(TASK_OVER);
  227. }
  228. else
  229. {
  230. //故障等级为 MAJOR_ERROR CRITICAL_ERROR,则雷达故障,不可以再接受任务单。
  231. m_laser_statu = LASER_FAULT;
  232. mp_laser_task->set_task_statu(TASK_ERROR);
  233. }
  234. }
  235. return Error_code::SUCCESS;
  236. }
  237. //取消任务单,由发送方提前取消任务单
  238. Error_manager Laser_base::cancel_task()
  239. {
  240. end_task();
  241. //强制改为 TASK_DEAD,不管它当前在做什么。
  242. mp_laser_task->set_task_statu(TASK_DEAD);
  243. return Error_code::SUCCESS;
  244. }
  245. //设置保存文件的路径,并打开文件,
  246. Error_manager Laser_base::set_open_save_path(std::string save_path,bool is_save)
  247. {
  248. m_save_flag = is_save;
  249. m_points_log_tool.close();
  250. m_binary_log_tool.close();
  251. if (is_save == false)
  252. {
  253. return Error_code::SUCCESS;
  254. }
  255. else
  256. {
  257. uint32_t beginCmpPath = 0;
  258. uint32_t endCmpPath = 0;
  259. std::string fullPath = save_path;
  260. if (fullPath[fullPath.size() - 1] != '/')
  261. {
  262. fullPath += "/";
  263. }
  264. fullPath += "laser_data/";
  265. endCmpPath = fullPath.size();
  266. //create dirs;
  267. for(uint32_t i = beginCmpPath; i < endCmpPath ; i++ )
  268. {
  269. if('/' == fullPath[i])
  270. {
  271. std::string curPath = fullPath.substr(0, i);
  272. if(access(curPath.c_str(), F_OK) != 0)
  273. {
  274. if(mkdir(curPath.c_str(),0777) == -1)
  275. {
  276. printf("mkdir(%s) failed\n", curPath.c_str());
  277. return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
  278. "set_open_save_path mkdir error ");
  279. }
  280. }
  281. }
  282. }
  283. time_t nowTime;
  284. nowTime = time(NULL);
  285. struct tm* sysTime = localtime(&nowTime);
  286. char time_string[256] = { 0 };
  287. sprintf(time_string, "%04d%02d%02d_%02d%02d%02d",
  288. sysTime->tm_year + 1900, sysTime->tm_mon + 1, sysTime->tm_mday, sysTime->tm_hour, sysTime->tm_min, sysTime->tm_sec);
  289. m_save_path = save_path;
  290. char pts_file[255] = { 0 };
  291. // sprintf(pts_file, "%s/pts%d.txt", save_path.c_str(), m_laser_id+1);
  292. sprintf(pts_file, "%s/laser_pst_%s__%d.txt", fullPath.c_str(), time_string, m_laser_id+0);
  293. m_points_log_tool.open(pts_file);
  294. // char bin_file[255] = { 0 };
  295. //// sprintf(bin_file, "%s/laser%d.data", save_path.c_str(), m_laser_id+1);
  296. // sprintf(bin_file, "%s/laser_binary_%s__%d.data", fullPath.c_str(),time_string, m_laser_id+1);
  297. // m_binary_log_tool.open(bin_file,true);
  298. // std::cout << "huli m_binary_log_tool path "<< bin_file << std::endl;
  299. return Error_code::SUCCESS;
  300. }
  301. }
  302. //关闭保存文件,推出前一定要执行
  303. Error_manager Laser_base::close_save_path()
  304. {
  305. m_save_flag = false;
  306. m_points_log_tool.close();
  307. m_binary_log_tool.close();
  308. return Error_code::SUCCESS;
  309. }
  310. //判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
  311. //子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
  312. bool Laser_base::is_ready()
  313. {
  314. return get_laser_statu() == LASER_READY ;
  315. }
  316. //获取雷达状态
  317. Laser_statu Laser_base::get_laser_statu()
  318. {
  319. return m_laser_statu;
  320. }
  321. //获取雷达id
  322. int Laser_base::get_laser_id()
  323. {
  324. return m_laser_id;
  325. }
  326. //线程执行函数,将二进制消息存入队列缓存,
  327. void Laser_base::thread_receive()
  328. {
  329. LOG(INFO) << " ---thread_receive start ---"<< this;
  330. Error_manager t_error;
  331. //接受雷达消息,每次循环只接受一个 Binary_buf
  332. while (m_condition_receive.is_alive())
  333. {
  334. m_condition_receive.wait();
  335. if ( m_condition_receive.is_alive() )
  336. {
  337. std::this_thread::yield();
  338. //获取雷达的通信消息缓存, ,并将其存入 m_queue_laser_data, 每次只转化一个CBinaryData,(循环执行)
  339. t_error = receive_buf_to_queue();
  340. if (t_error == SUCCESS)
  341. {
  342. //这里非常特殊,receive_buf_to_queue会为 Binary_buf 分配内存. 是new出来的
  343. //此时 Binary_buf 的内存管理权限转交给 m_queue_laser_data .之后由 Laser_base 负责管理.
  344. ;
  345. }
  346. //接受线程无法接受到数据的同时,也收到了雷达停止扫描的信息,那么线程停止
  347. //如果m_laser_scan_flag停止扫描,但是receive_buf_to_queue仍然能够接受到数据。那么线程继续运行。
  348. //m_laser_scan_flag停止的瞬间,可能还有残留的数据,需要继续执行。
  349. else if(t_error == NO_DATA )
  350. {
  351. if ( !m_laser_scan_flag )
  352. {
  353. //停止线程,m_condition_receive.wait() 函数将会阻塞。正常停止接受线程
  354. m_condition_receive.set_pass_ever(false);
  355. //注:此时thread_transform线程仍然继续,任务也没有停止.
  356. }
  357. }
  358. else
  359. {
  360. //因为故障,而提前结束任务.
  361. mp_laser_task->compare_and_cover_task_error_manager(t_error);
  362. end_task();
  363. }
  364. }
  365. }
  366. LOG(INFO) << " thread_receive end :"<<this;
  367. return;
  368. }
  369. //线程执行函数,转化并处理三维点云。
  370. void Laser_base::thread_transform()
  371. {
  372. LOG(INFO) << " thread_transform start "<< this;
  373. Error_manager t_error;
  374. //转化雷达数据,每次循环只转化一个 Binary_buf,然后得到 t_point3D_cloud.size() 个三维点,
  375. while (m_condition_transform.is_alive())
  376. {
  377. m_condition_transform.wait();
  378. if ( m_condition_transform.is_alive() )
  379. {
  380. std::this_thread::yield();
  381. t_error = transform_buf_to_points();
  382. if ( t_error == SUCCESS )
  383. {
  384. ;
  385. }
  386. //转化线程 不需要数据的同时,也收到了雷达停止扫描的信息并且接受线程已经停止,那么停止转化线程,
  387. //注:必须先停止接受线程,再停止转化线程。转化线程停止之后即可结束任务。
  388. //如果m_laser_scan_flag停止扫描,接受线程和转化线程还有未完成的数据。那么线程继续运行。
  389. //m_laser_scan_flag停止的瞬间,可能还有残留的数据,需要继续执行。防止数据遗留。
  390. else if (t_error == NO_DATA )
  391. {
  392. if(m_laser_scan_flag == false && m_condition_receive.get_pass_ever() == false)
  393. {
  394. //停止转化线程,m_condition_transform.wait() 函数将会阻塞。
  395. m_condition_transform.set_pass_ever(false);
  396. //mp_thread_transform 停止时,雷达扫描任务彻底完成,此时任务正常结束
  397. end_task();
  398. }
  399. }
  400. else
  401. {
  402. //因为故障,而提前结束任务.
  403. mp_laser_task->compare_and_cover_task_error_manager(t_error);
  404. end_task();
  405. }
  406. }
  407. }
  408. LOG(INFO) << " thread_transform end "<< this;
  409. return;
  410. }
  411. //公开发布雷达信息的功能函数,
  412. Error_manager Laser_base::publish_laser_to_message()
  413. {
  414. return Error_code::SUCCESS;
  415. /*
  416. globalmsg::msg msg;
  417. msg.set_msg_type(globalmsg::eLaser);
  418. globalmsg::laserStatus status;
  419. if(GetStatu()==eLaser_ready) status=globalmsg::eLaserConnected;
  420. else if(GetStatu()==eLaser_disconnect) status=globalmsg::eLaserDisconnected;
  421. else if(GetStatu()==eLaser_busy) status=globalmsg::eLaserBusy;
  422. else status=globalmsg::eLaserUnknown;
  423. msg.mutable_laser_msg()->set_id(m_laser_id);
  424. msg.mutable_laser_msg()->set_laser_status(status);
  425. msg.mutable_laser_msg()->set_queue_data_count(m_queue_laser_data.size());
  426. msg.mutable_laser_msg()->set_cloud_count(m_points_count);
  427. MeasureTopicPublisher::GetInstance()->Publish(msg.SerializeAsString());
  428. */
  429. }
  430. //线程执行函数,公开发布雷达的相关信息,用作上位机的监视。
  431. void Laser_base::thread_publish(Laser_base *p_laser)
  432. {
  433. LOG(INFO) << " thread_publish start ";
  434. if(p_laser==NULL)
  435. {
  436. return;
  437. }
  438. while (p_laser->m_condition_publish.is_alive())
  439. {
  440. p_laser->m_condition_publish.wait();
  441. if ( p_laser->m_condition_publish.is_alive() )
  442. {
  443. p_laser->publish_laser_to_message();
  444. //每隔300ms,发送一次雷达信息状态。
  445. std::this_thread::sleep_for(std::chrono::milliseconds(300));
  446. }
  447. }
  448. LOG(INFO) << " thread_publish end ";
  449. return;
  450. }
  451. //初始化变换矩阵,设置默认值
  452. Error_manager Laser_base::init_laser_matrix()
  453. {
  454. if ( LASER_MATRIX_ARRAY_SIZE == 12 )
  455. {
  456. //详见转化的算法transfor。保证转化前后坐标一致。
  457. mp_laser_matrix[0] = 1;
  458. mp_laser_matrix[1] = 0;
  459. mp_laser_matrix[2] = 0;
  460. mp_laser_matrix[3] = 0;
  461. mp_laser_matrix[4] = 0;
  462. mp_laser_matrix[5] = 1;
  463. mp_laser_matrix[6] = 0;
  464. mp_laser_matrix[7] = 0;
  465. mp_laser_matrix[8] = 0;
  466. mp_laser_matrix[9] = 0;
  467. mp_laser_matrix[10] = 1;
  468. mp_laser_matrix[11] = 0;
  469. }
  470. else
  471. {
  472. for (int i = 0; i < LASER_MATRIX_ARRAY_SIZE; ++i)
  473. {
  474. //设为0之后,变换之后,新的点坐标全部为0
  475. mp_laser_matrix[i] = 0;
  476. }
  477. }
  478. return Error_code::SUCCESS;
  479. }
  480. //设置变换矩阵,用作三维点的坐标变换,
  481. Error_manager Laser_base::set_laser_matrix(double* p_matrix, int size)
  482. {
  483. if ( p_matrix == NULL )
  484. {
  485. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  486. " set_laser_matrix p_matrix IS_NULL ");
  487. }
  488. else if ( size != LASER_MATRIX_ARRAY_SIZE )
  489. {
  490. return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
  491. " set_laser_matrix size is not Match");
  492. }
  493. else
  494. {
  495. memcpy(mp_laser_matrix, p_matrix, LASER_MATRIX_ARRAY_SIZE * sizeof(double));
  496. return Error_code::SUCCESS;
  497. }
  498. return Error_code::SUCCESS;
  499. }
  500. //三维点的坐标变换的功能函数,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
  501. CPoint3D Laser_base::transform_by_matrix(CPoint3D point)
  502. {
  503. CPoint3D result;
  504. double x = point.x;
  505. double y = point.y;
  506. double z = point.z;
  507. result.x = x * mp_laser_matrix[0] + y*mp_laser_matrix[1] + z*mp_laser_matrix[2] + mp_laser_matrix[3];
  508. result.y = x * mp_laser_matrix[4] + y*mp_laser_matrix[5] + z*mp_laser_matrix[6] + mp_laser_matrix[7];
  509. result.z = x * mp_laser_matrix[8] + y*mp_laser_matrix[9] + z*mp_laser_matrix[10] + mp_laser_matrix[11];
  510. return result;
  511. }