region_worker.cpp 8.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243
  1. //
  2. // Created by zx on 2019/12/9.
  3. //
  4. #include "region_worker.h"
  5. //#include "plc_data.h"
  6. Region_worker::Region_worker()
  7. {
  8. m_region_worker_status = E_UNKNOWN;
  9. mp_cloud_collection_mutex = NULL;
  10. mp_cloud_collection = NULL;
  11. m_detect_updata_time = std::chrono::system_clock::now() - std::chrono::hours(1);
  12. mp_auto_detect_thread = NULL;
  13. }
  14. /**
  15. * 析构
  16. * */
  17. Region_worker::~Region_worker()
  18. {
  19. }
  20. Error_manager Region_worker::init(Point2D_tool::Point2D_box point2D_box, std::mutex* p_cloud_collection_mutex,
  21. pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_collection)
  22. {
  23. m_detector.init(point2D_box);
  24. mp_cloud_collection_mutex = p_cloud_collection_mutex;
  25. mp_cloud_collection = p_cloud_collection;
  26. m_auto_detect_condition.reset(false, false, false);
  27. mp_auto_detect_thread = new std::thread(&Region_worker::auto_detect_thread_fun, this);
  28. m_region_worker_status = E_READY;
  29. return Error_code::SUCCESS;
  30. }
  31. //开始自动预测的算法线程
  32. Error_manager Region_worker::start_auto_detect()
  33. {
  34. //唤醒一次
  35. m_auto_detect_condition.notify_all(false, true);
  36. return Error_code::SUCCESS;
  37. }
  38. //关闭自动预测的算法线程
  39. Error_manager Region_worker::stop_auto_detect()
  40. {
  41. //唤醒一次
  42. m_auto_detect_condition.notify_all(false);
  43. return Error_code::SUCCESS;
  44. }
  45. // 获得中心点、角度等测量数据
  46. Error_manager Region_worker::detect_wheel_result(std::mutex* p_cloud_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in, Common_data::Car_wheel_information& car_wheel_information)
  47. {
  48. return m_detector.detect(p_cloud_mutex, p_cloud_in, car_wheel_information);
  49. }
  50. // 获得中心点、角度等测量数据, 新算法, 可以测量前轮旋转
  51. Error_manager Region_worker::detect_wheel_result_ex(std::mutex* p_cloud_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in, Common_data::Car_wheel_information& car_wheel_information)
  52. {
  53. return m_detector.detect_ex(p_cloud_mutex, p_cloud_in, car_wheel_information);
  54. }
  55. //外部调用获取新的车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会等待车轮定位信息刷新, 直到超时, (内置while)
  56. Error_manager Region_worker::get_new_wheel_information_and_wait(Common_data::Car_wheel_information* p_car_wheel_information,
  57. std::chrono::system_clock::time_point command_time, int timeout_ms)
  58. {
  59. if ( p_car_wheel_information == NULL )
  60. {
  61. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  62. " POINTER IS NULL ");
  63. }
  64. //判断是否超时
  65. while (std::chrono::system_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
  66. {
  67. //获取指令时间之后的信息, 如果没有就会循环
  68. if(m_detect_updata_time > command_time )
  69. {
  70. *p_car_wheel_information = m_car_wheel_information;
  71. return Error_code::SUCCESS;
  72. }
  73. //else 等待下一次数据更新
  74. //等1ms
  75. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  76. }
  77. //超时退出就报错
  78. return Error_manager(Error_code::WJ_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  79. " Region_worker::get_new_wheel_information_and_wait error ");
  80. }
  81. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  82. Error_manager Region_worker::get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  83. std::chrono::system_clock::time_point command_time)
  84. {
  85. if ( p_car_wheel_information == NULL )
  86. {
  87. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  88. " POINTER IS NULL ");
  89. }
  90. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  91. if( m_detect_updata_time > command_time )
  92. {
  93. *p_car_wheel_information = m_car_wheel_information;
  94. return Error_code::SUCCESS;
  95. }
  96. else
  97. {
  98. return Error_manager(Error_code::WJ_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  99. " Region_worker::get_current_wheel_information error ");
  100. }
  101. }
  102. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  103. Error_manager Region_worker::get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  104. std::chrono::system_clock::time_point command_time)
  105. {
  106. if ( p_car_wheel_information == NULL )
  107. {
  108. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  109. " POINTER IS NULL ");
  110. }
  111. //将指令时间提前一个扫描周期, 然后获取这个时间后面的点云.
  112. //就是说, 在收到指令的时候, 可以使用一个周期以前的数据, 不用获取最新的点云.
  113. if( m_detect_updata_time > command_time - std::chrono::milliseconds(REGION_WORKER_DETECT_CYCLE_MS) )
  114. {
  115. *p_car_wheel_information = m_car_wheel_information;
  116. return Error_code::SUCCESS;
  117. }
  118. else
  119. {
  120. return Error_manager(Error_code::WJ_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  121. " Region_worker::get_last_wheel_information error ");
  122. }
  123. }
  124. Region_worker::Region_worker_status Region_worker::get_status()
  125. {
  126. return m_region_worker_status;
  127. }
  128. std::chrono::system_clock::time_point Region_worker::get_detect_updata_time()
  129. {
  130. return m_detect_updata_time;
  131. }
  132. cv::RotatedRect Region_worker::create_rotate_rect(float length,float width,float angle,float cx,float cy)
  133. {
  134. const double C_PI=3.14159265;
  135. float theta=C_PI*(angle/180.0);
  136. float a00=cos(theta);
  137. float a01=-sin(theta);
  138. float a10=sin(theta);
  139. float a11=cos(theta);
  140. cv::Point2f point[4];
  141. point[0].x=-length/2.0;
  142. point[0].y=-width/2.0;
  143. point[1].x=-length/2.0;
  144. point[1].y=width/2.0;
  145. point[2].x=length/2.0;
  146. point[2].y=-width/2.0;
  147. point[3].x=length/2.0;
  148. point[3].y=width/2.0;
  149. std::vector<cv::Point2f> point_vec;
  150. for(int i=0;i<4;++i)
  151. {
  152. float x=point[i].x*a00+point[i].y*a01+cx;
  153. float y=point[i].x*a10+point[i].y*a11+cy;
  154. point_vec.push_back(cv::Point2f(x,y));
  155. }
  156. return cv::minAreaRect(point_vec);
  157. }
  158. //自动预测的线程函数
  159. void Region_worker::auto_detect_thread_fun()
  160. {
  161. LOG(INFO) << " Wanji_manager::collect_cloud_thread_fun() start "<< this;
  162. Error_manager t_error;
  163. Error_manager t_result;
  164. while (m_auto_detect_condition.is_alive())
  165. {
  166. //暂时固定为一个扫描周期, 就循环一次
  167. //后期可以根据每个小雷达的刷新情况, 实时更改总点云.....
  168. m_auto_detect_condition.wait();
  169. if ( m_auto_detect_condition.is_alive() )
  170. {
  171. // std::cout << " huli test :::: " << " = " << "---------------------------------------------------------------------------------" << std::endl;
  172. //
  173. // std::cout << " huli test :::: " << " mp_cloud_collection->size() = " << mp_cloud_collection->size() << std::endl;
  174. //
  175. // auto start = std::chrono::system_clock::now();
  176. t_error = detect_wheel_result_ex(mp_cloud_collection_mutex, mp_cloud_collection, m_car_wheel_information);
  177. // auto end = std::chrono::system_clock::now();
  178. // auto duration = std::chrono::duration_cast<std::chrono::microseconds>(end - start);
  179. // std::cout << "花费了"
  180. // << double(duration.count()*1000) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den << "毫秒" << std::endl;
  181. if ( t_error == SUCCESS )
  182. {
  183. std::unique_lock<std::mutex> t_lock(*mp_cloud_collection_mutex);
  184. m_car_wheel_information.correctness = true;
  185. // std::cout << " huli test :::: " << " x = " << m_car_wheel_information.center_x << std::endl;
  186. // std::cout << " huli test :::: " << " y = " << m_car_wheel_information.center_y << std::endl;
  187. // std::cout << " huli test :::: " << " c = " << m_car_wheel_information.car_angle << std::endl;
  188. // std::cout << " huli test :::: " << " wheelbase = " << m_car_wheel_information.wheel_base << std::endl;
  189. // std::cout << " huli test :::: " << " width = " << m_car_wheel_information.wheel_width << std::endl;
  190. // std::cout << " huli test :::: " << " front_theta = " << m_car_wheel_information.front_theta << std::endl;
  191. // std::cout << " huli test :::: " << " correctness = " << m_car_wheel_information.correctness << std::endl;
  192. }
  193. else
  194. {
  195. std::unique_lock<std::mutex> t_lock(*mp_cloud_collection_mutex);
  196. m_car_wheel_information.correctness = false;
  197. // std::cout << " huli test :::: " << " t_error = " << t_error << std::endl;
  198. }
  199. //无论结果如何,都要刷新时间, 表示这次定位已经执行了.
  200. m_detect_updata_time = std::chrono::system_clock::now();
  201. }
  202. }
  203. LOG(INFO) << " Wanji_manager::collect_cloud_thread_fun() end "<< this;
  204. return;
  205. }