wanji_716N_device.cpp 9.2 KB

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