wanji_716N_device.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263
  1. #include "wanji_716N_device.h"
  2. // 万集雷达封装类构造函数
  3. Wanji_716N_lidar_device::Wanji_716N_lidar_device()
  4. {
  5. m_wanji_lidar_device_status = E_UNKNOWN;
  6. }
  7. // 万集雷达封装类析构函数
  8. Wanji_716N_lidar_device::~Wanji_716N_lidar_device()
  9. {
  10. uninit();
  11. }
  12. // 初始化
  13. Error_manager Wanji_716N_lidar_device::init(std::string t_ip,int t_port,
  14. Point2D_tool::Polar_coordinates_box t_polar_coordinates_box,
  15. Point2D_tool::Point2D_box t_point2D_box,
  16. Point2D_tool::Point2D_transform t_point2D_transform)
  17. {
  18. Error_manager t_error;
  19. LOG(INFO) << " Wanji_716N_lidar_device::init "<< this;
  20. //唤醒队列
  21. m_communication_data_queue.wake_queue();
  22. t_point2D_transform.m00 = 1;
  23. t_point2D_transform.m01 = 0;
  24. t_point2D_transform.m02 = 0;
  25. t_point2D_transform.m10 = 0;
  26. t_point2D_transform.m11 = 1;
  27. t_point2D_transform.m12 = 0;
  28. //初始化通信协议
  29. t_error = m_protocol.init(&m_communication_data_queue, t_polar_coordinates_box, t_point2D_box, t_point2D_transform);
  30. if (t_error != SUCCESS)
  31. {
  32. return t_error;
  33. }
  34. //初始化雷达通信模块
  35. t_error = m_async_client.init(t_ip, t_port, &m_communication_data_queue);
  36. if ( t_error != SUCCESS )
  37. {
  38. return t_error;
  39. }
  40. //启动 内部线程。默认wait。
  41. m_execute_condition.reset(false, false, false);
  42. // mp_execute_thread = new std::thread(&Wanji_716N_lidar_device::execute_thread_fun, this);
  43. m_wanji_lidar_device_status = E_READY;
  44. return t_error;
  45. }
  46. //反初始化
  47. Error_manager Wanji_716N_lidar_device::uninit()
  48. {
  49. //终止队列,防止 wait_and_pop 阻塞线程。
  50. m_communication_data_queue.termination_queue();
  51. //关闭线程
  52. if (mp_execute_thread)
  53. {
  54. m_execute_condition.kill_all();
  55. }
  56. //回收线程的资源
  57. if (mp_execute_thread)
  58. {
  59. mp_execute_thread->join();
  60. delete mp_execute_thread;
  61. mp_execute_thread = NULL;
  62. }
  63. m_async_client.uninit();
  64. m_protocol.uninit();
  65. //清空队列
  66. m_communication_data_queue.clear_and_delete();
  67. if ( m_wanji_lidar_device_status != E_FAULT )
  68. {
  69. m_wanji_lidar_device_status = E_UNKNOWN;
  70. }
  71. return Error_code::SUCCESS;
  72. }
  73. //检查雷达状态,是否正常运行
  74. Error_manager Wanji_716N_lidar_device::check_status()
  75. {
  76. updata_status();
  77. if ( m_wanji_lidar_device_status == E_READY )
  78. {
  79. return Error_code::SUCCESS;
  80. }
  81. else if(m_wanji_lidar_device_status == E_BUSY)
  82. {
  83. return Error_manager(Error_code::WANJI_LIDAR_DEVICE_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
  84. " Wanji_716N_lidar_device::check_status() error ");
  85. }
  86. else
  87. {
  88. return Error_manager(Error_code::WANJI_LIDAR_DEVICE_STATUS_ERROR, Error_level::MINOR_ERROR,
  89. " Wanji_716N_lidar_device::check_status() error ");
  90. }
  91. return Error_code::SUCCESS;
  92. }
  93. //判断是否为待机,如果已经准备好,则可以执行任务。
  94. bool Wanji_716N_lidar_device::is_ready()
  95. {
  96. updata_status();
  97. return m_wanji_lidar_device_status == E_READY;
  98. }
  99. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  100. Error_manager Wanji_716N_lidar_device::get_new_cloud_and_wait(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  101. std::chrono::system_clock::time_point command_time, int timeout_ms)
  102. {
  103. if ( p_mutex == NULL || p_cloud.get() == NULL )
  104. {
  105. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  106. " POINTER IS NULL ");
  107. }
  108. //判断是否超时
  109. while (std::chrono::system_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
  110. {
  111. //获取指令时间之后的点云, 如果没有就会循环
  112. if( m_protocol.get_scan_time() > command_time )
  113. {
  114. std::unique_lock<std::mutex> lck(*p_mutex);
  115. Error_manager code = m_protocol.get_scan_points(p_cloud);
  116. return code;
  117. }
  118. //else 等待下一次数据更新
  119. //等1ms
  120. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  121. }
  122. //超时退出就报错
  123. return Error_manager(Error_code::WJ_LIDAR_GET_CLOUD_TIMEOUT, Error_level::MINOR_ERROR,
  124. " Wanji_716N_lidar_device::get_new_cloud_and_wait error ");
  125. }
  126. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  127. Error_manager Wanji_716N_lidar_device::get_current_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  128. std::chrono::system_clock::time_point command_time)
  129. {
  130. if ( p_mutex == NULL || p_cloud.get() == NULL )
  131. {
  132. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  133. " POINTER IS NULL ");
  134. }
  135. //获取指令时间之后的点云, 如果没有就会报错, 不会等待
  136. if( m_protocol.get_scan_time() > command_time )
  137. {
  138. std::unique_lock<std::mutex> lck(*p_mutex);
  139. Error_manager code = m_protocol.get_scan_points(p_cloud);
  140. return code;
  141. }
  142. else
  143. {
  144. return Error_manager(Error_code::WANJI_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  145. " Wanji_716N_lidar_device::get_current_cloud error ");
  146. }
  147. }
  148. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  149. Error_manager Wanji_716N_lidar_device::get_last_cloud(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  150. std::chrono::system_clock::time_point command_time)
  151. {
  152. if ( p_mutex == NULL || p_cloud.get() == NULL )
  153. {
  154. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  155. " POINTER IS NULL ");
  156. }
  157. int t_scan_cycle_ms = m_protocol.get_scan_cycle();
  158. //将指令时间提前一个扫描周期, 然后获取这个时间后面的点云.
  159. //就是说, 在收到指令的时候, 可以使用一个周期以前的数据, 不用获取最新的点云.
  160. if( m_protocol.get_scan_time() > command_time - std::chrono::milliseconds(t_scan_cycle_ms) )
  161. {
  162. std::unique_lock<std::mutex> lck(*p_mutex);
  163. Error_manager code = m_protocol.get_scan_points(p_cloud);
  164. return code;
  165. }
  166. else
  167. {
  168. return Error_manager(Error_code::WANJI_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  169. " Wanji_716N_lidar_device::get_last_cloud error ");
  170. }
  171. }
  172. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  173. //注:函数内部不加锁, 由外部统一加锁.
  174. Error_manager Wanji_716N_lidar_device::get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  175. std::chrono::system_clock::time_point command_time)
  176. {
  177. if ( p_cloud.get() == NULL )
  178. {
  179. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  180. " POINTER IS NULL ");
  181. }
  182. int t_scan_cycle_ms = m_protocol.get_scan_cycle();
  183. //将指令时间提前一个扫描周期, 然后获取这个时间后面的点云.
  184. //就是说, 在收到指令的时候, 可以使用一个周期以前的数据, 不用获取最新的点云.
  185. if( m_protocol.get_scan_time() > command_time - std::chrono::milliseconds(t_scan_cycle_ms*2) )
  186. {
  187. Error_manager code = m_protocol.get_scan_points(p_cloud);
  188. // LOG(WARNING) << " !!!!!!!!!!!!! wj scan cloud: "<<p_cloud->size();
  189. return code;
  190. }
  191. else
  192. {
  193. // LOG(WARNING) << "get cloud failed..... "<<m_protocol.get_scan_time().time_since_epoch().count()<<", "<<command_time.time_since_epoch().count();
  194. return Error_manager(Error_code::WANJI_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  195. " Wanji_716N_lidar_device::get_last_cloud error ");
  196. }
  197. }
  198. Wanji_716N_lidar_device::Wanji_716N_device_status Wanji_716N_lidar_device::get_status()
  199. {
  200. updata_status();
  201. return m_wanji_lidar_device_status;
  202. }
  203. void Wanji_716N_lidar_device::updata_status()
  204. {
  205. Async_Client::Communication_status communication_status = m_async_client.get_status();
  206. // Wj_716N_lidar_protocol::Wanji_716N_device_status wanji_lidar_protocol_status = m_protocol.get_status();
  207. if ( communication_status == Async_Client::Communication_status::E_FAULT)// ||
  208. // wanji_lidar_protocol_status == Wj_716N_lidar_protocol::Wanji_716N_device_status::E_FAULT)
  209. {
  210. m_wanji_lidar_device_status = E_FAULT;
  211. }
  212. if ( communication_status == Async_Client::Communication_status::E_DISCONNECT )
  213. {
  214. m_wanji_lidar_device_status = E_DISCONNECT;
  215. }
  216. else if ( communication_status == Async_Client::Communication_status::E_READY)// &&
  217. // wanji_lidar_protocol_status == Wj_716N_lidar_protocol::Wanji_716N_device_status::E_READY )
  218. {
  219. if ( m_execute_condition.get_pass_ever() )
  220. {
  221. m_wanji_lidar_device_status = E_BUSY;
  222. }
  223. else
  224. {
  225. m_wanji_lidar_device_status = E_READY;
  226. }
  227. }
  228. else
  229. {
  230. m_wanji_lidar_device_status = E_UNKNOWN;
  231. }
  232. }