locater.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382
  1. //
  2. // Created by zx on 2019/12/30.
  3. //
  4. #include "locater.h"
  5. #include <pcl/filters//voxel_grid.h>
  6. #include <pcl/filters/passthrough.h>
  7. #include <glog/logging.h>
  8. Locater::Locater():mp_yolo_detector(0),mp_point_sift(0),mp_cnn3d(0)
  9. {
  10. }
  11. Locater::~Locater()
  12. {}
  13. Error_manager Locater::get_error()
  14. {
  15. return SUCCESS;
  16. }
  17. Error_manager Locater::init(Measure::LocateParameter parameter)
  18. {
  19. Error_manager code;
  20. {
  21. int point_size = parameter.seg_parameter().point_size();
  22. int cls_num = parameter.seg_parameter().cls_num();
  23. double freq = parameter.seg_parameter().freq();
  24. std::string graph = parameter.seg_parameter().graph();
  25. std::string cpkt = parameter.seg_parameter().cpkt();
  26. Measure::Area3d area = parameter.seg_parameter().area();
  27. pcl::PointXYZ minp(area.x_min(), area.y_min(), area.z_min());
  28. pcl::PointXYZ maxp(area.x_max(), area.y_max(), area.z_max());
  29. LOG(INFO)<<"Creating pointSift net ...";
  30. mp_point_sift = new Point_sift_segmentation(point_size,cls_num,freq,minp,maxp);
  31. std::string graph_file = graph;
  32. std::string cpkt_file = cpkt;
  33. LOG(INFO)<<"init pointSift net graph:"<<graph;
  34. code=mp_point_sift->init(graph_file,cpkt_file);
  35. if(code!=SUCCESS)
  36. {
  37. LOG(ERROR)<<code.to_string();
  38. return code;
  39. }
  40. }
  41. {
  42. LOG(INFO)<<"Creating darknet ...";
  43. float min_x = parameter.yolo_parameter().min_x();
  44. float max_x = parameter.yolo_parameter().max_x();
  45. float min_y = parameter.yolo_parameter().min_y();
  46. float max_y = parameter.yolo_parameter().max_y();
  47. float freq = parameter.yolo_parameter().freq();
  48. std::string cfg = parameter.yolo_parameter().cfg();
  49. std::string weights = parameter.yolo_parameter().weights();
  50. mp_yolo_detector = new YoloDetector(cfg, weights, min_x, max_x, min_y, max_y, freq);
  51. }
  52. int l = parameter.net_3dcnn_parameter().length();
  53. int w = parameter.net_3dcnn_parameter().width();
  54. int h = parameter.net_3dcnn_parameter().height();
  55. int nClass = parameter.net_3dcnn_parameter().nclass();
  56. int freq = parameter.net_3dcnn_parameter().freq();
  57. mp_cnn3d = new Cnn3d_segmentation(l, w, h, freq, nClass);
  58. LOG(INFO)<<"Init 3dcnn ...";
  59. std::string weights = parameter.net_3dcnn_parameter().weights_file();
  60. code=mp_cnn3d->init(weights);
  61. if(code!=SUCCESS)
  62. {
  63. return code;
  64. }
  65. return SUCCESS;
  66. }
  67. Error_manager Locater::execute_task(Task_Base* task,double time_out)
  68. {
  69. LOG(INFO)<<"NEW LOCATE TASK ==============================================================================";
  70. Locate_information locate_information;
  71. locate_information.locate_correct=false;
  72. //判断task是否合法
  73. if(task==0) return LOCATER_TASK_ERROR;
  74. if(task->get_task_type()!=LOCATE_TASK)
  75. {
  76. task->update_statu(TASK_OVER,"locate task type error");
  77. return Error_manager(LOCATER_TASK_ERROR,NORMAL,"locate Task type error");
  78. }
  79. Locate_task* locate_task=(Locate_task*)task;
  80. locate_task->update_statu(TASK_SIGNED);
  81. Error_manager code;
  82. ///第一步,获取task中input点云,文件保存路径
  83. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud_input=locate_task->get_locate_cloud();
  84. std::string save_path=locate_task->get_save_path();
  85. if(t_cloud_input.get()==0)
  86. {
  87. locate_task->update_statu(TASK_OVER,"Task set cloud is uninit");
  88. return Error_manager(LOCATER_INPUT_CLOUD_UNINIT,NORMAL,"Task set cloud is uninit");
  89. }
  90. //第二步,加锁,更新task状态,调用locate,进入测量中
  91. std::lock_guard<std::mutex> t_lock(m_mutex_lock);
  92. locate_task->update_statu(TASK_WORKING);
  93. code=locate(t_cloud_input,locate_information,save_path);
  94. locate_task->set_locate_information(locate_information);
  95. if(code!=SUCCESS)
  96. {
  97. locate_task->update_statu(TASK_OVER,"Locate Failed");
  98. return code;
  99. }
  100. locate_task->update_statu(TASK_OVER,"Locate OK");
  101. return code;
  102. }
  103. Error_manager Locater::locate_yolo(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
  104. std::vector<YoloBox>& boxes, std::string work_dir)
  105. {
  106. if(cloud_in.get()==0)
  107. {
  108. return Error_manager(LOCATER_YOLO_INPUT_CLOUD_UNINIT,NORMAL,"yolo input cloud uninit");
  109. }
  110. if(cloud_in->size()==0)
  111. {
  112. return Error_manager(LOCATER_INPUT_YOLO_CLOUD_EMPTY,NORMAL,"locate_yolo input cloud empty");
  113. }
  114. if(mp_yolo_detector==0)
  115. {
  116. return Error_manager(LOCATER_YOLO_UNINIT,NORMAL,"locate_yolo yolo is not init");
  117. }
  118. //1,根据点云区域,调整yolo边界参数,边界参数必须保证长宽 1:1
  119. pcl::PointXYZ min_point,max_point;
  120. pcl::getMinMax3D(*cloud_in,min_point,max_point);
  121. float yolo_minx=min_point.x;
  122. float yolo_maxx=max_point.x;
  123. float yolo_miny=min_point.y;
  124. float yolo_maxy=max_point.y;
  125. float length=yolo_maxx-yolo_minx;
  126. float width=yolo_maxy-yolo_miny;
  127. if(length>2*width) yolo_maxy=(length/2.0)+yolo_miny;
  128. else if(length<2*width) yolo_maxx=(2*width)+yolo_minx;
  129. Error_manager code=mp_yolo_detector->set_region(yolo_minx,yolo_maxx,yolo_miny,
  130. yolo_maxy,m_locate_parameter.yolo_parameter().freq());
  131. if(code!=SUCCESS)
  132. {
  133. return code;
  134. }
  135. //2,识别车辆位置
  136. boxes.clear();
  137. return mp_yolo_detector->detect(cloud_in,boxes,work_dir);
  138. }
  139. Error_manager Locater::locate_sift(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox> boxes,
  140. pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_wheel,pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_car,
  141. std::string work_dir)
  142. {
  143. if(cloud_in.get()==0)
  144. {
  145. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,NORMAL,"sift input cloud uninit");
  146. }
  147. if(cloud_in->size()==0)
  148. {
  149. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,NORMAL,"locate_sift input cloud empty");
  150. }
  151. if(mp_point_sift==0)
  152. {
  153. return Error_manager(LOCATER_POINTSIFT_UNINIT,NORMAL,"Point Sift unInit");
  154. }
  155. //第一步,根据点云边界调整PointSIft 参数
  156. pcl::PointXYZ min_point,max_point;
  157. pcl::getMinMax3D(*cloud_in,min_point,max_point);
  158. Error_manager code ;
  159. code=mp_point_sift->set_region(min_point,max_point);
  160. if(code!=SUCCESS)
  161. {
  162. return code;
  163. }
  164. //第二步,点云抽稀,抽稀后的点云大约在8192左右,
  165. // 如果有多辆车(多个yolo框),取第一个框
  166. YoloBox yolo_box=boxes[0];
  167. pcl::PointXYZ minp, maxp;
  168. minp.x = yolo_box.x;
  169. minp.y = yolo_box.y;
  170. maxp.x = minp.x + yolo_box.w;
  171. maxp.y = minp.y + yolo_box.h;
  172. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_input_sift(new pcl::PointCloud<pcl::PointXYZ>());
  173. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_downsample(new pcl::PointCloud<pcl::PointXYZ>());
  174. /// ///体素网格 下采样
  175. pcl::VoxelGrid<pcl::PointXYZ> vgfilter;
  176. vgfilter.setInputCloud(cloud_in);
  177. vgfilter.setLeafSize(60.f, 60.f, 50.f);
  178. vgfilter.filter(*cloud_downsample);
  179. //限制 x y
  180. pcl::PassThrough<pcl::PointXYZ> passX;
  181. pcl::PassThrough<pcl::PointXYZ> passY;
  182. pcl::PassThrough<pcl::PointXYZ> passZ;
  183. passX.setInputCloud(cloud_downsample);
  184. passX.setFilterFieldName("x");
  185. passX.setFilterLimits(minp.x, maxp.x);
  186. passX.filter(*cloud_in);
  187. passY.setInputCloud(cloud_in);
  188. passY.setFilterFieldName("y");
  189. passY.setFilterLimits(minp.y, maxp.y);
  190. passY.filter(*cloud_in);
  191. passY.setInputCloud(cloud_in);
  192. passY.setFilterFieldName("z");
  193. passY.setFilterLimits(40, 2000);
  194. passY.filter(*cloud_in);
  195. //第三步,分割车辆点云
  196. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> segmentation_clouds;
  197. code=mp_point_sift->seg(cloud_in, segmentation_clouds, work_dir);
  198. if(code!=SUCCESS)
  199. {
  200. return code;
  201. }
  202. if(segmentation_clouds[0]->size()==0||segmentation_clouds[2]->size()==0)
  203. {
  204. return Error_manager(LOCATER_SIFT_PREDICT_NO_CAR_POINT,NORMAL,"sift predict no car or wheel");
  205. }
  206. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud_car(new pcl::PointCloud<pcl::PointXYZ>);
  207. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud_wheel(new pcl::PointCloud<pcl::PointXYZ>);
  208. //第0类即是轮胎点云,第二类为车身点云
  209. pcl::copyPointCloud(*segmentation_clouds[0], *t_cloud_wheel);
  210. pcl::copyPointCloud(*segmentation_clouds[2], *t_cloud_car);
  211. cloud_wheel=t_cloud_wheel;
  212. cloud_car=t_cloud_car;
  213. return SUCCESS;
  214. }
  215. Error_manager Locater::locate_wheel(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  216. float& center_x,float& center_y,
  217. float& wheel_base,float& width,float& angle,
  218. std::string work_dir)
  219. {
  220. if(cloud.get()==0)
  221. {
  222. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_UNINIT,NORMAL,"3dcnn input cloud uninit");
  223. }
  224. if(cloud->size()==0)
  225. {
  226. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,NORMAL,"locate_3dcnn input cloud empty");
  227. }
  228. if(mp_cnn3d==0)
  229. {
  230. return Error_manager(LOCATER_3DCNN_UNINIT,NORMAL,"locate_wheel 3dcnn is not init");
  231. }
  232. //识别车轮
  233. Error_manager code;
  234. code=mp_cnn3d->predict(cloud,center_x,center_y,wheel_base,width,angle,work_dir);
  235. if(code!=SUCCESS)
  236. {
  237. return code;
  238. }
  239. //根据plc限制判断合法性
  240. if(center_y>=930 || center_y<=200)
  241. {
  242. char description[255]={0};
  243. sprintf(description,"Y is out of range by plc (200 , 900) Y:%.2f",center_y);
  244. return Error_manager(LOCATER_Y_OUT_RANGE_BY_PLC,NORMAL,description);
  245. }
  246. return SUCCESS;
  247. }
  248. Error_manager Locater::measure_height(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car,float& height)
  249. {
  250. if(cloud_car.get()==0)
  251. {
  252. return Error_manager(LOCATER_MEASURE_HEIGHT_CLOUD_UNINIT,NORMAL,"measure height input cloud uninit");
  253. }
  254. if(cloud_car->size()==0)
  255. {
  256. return Error_manager(LOCATER_MEASURE_HEIGHT_CLOUD_EMPTY,NORMAL,"measure height input cloud is empty");
  257. }
  258. pcl::PointXYZ min_point,max_point;
  259. pcl::getMinMax3D(*cloud_car,min_point,max_point);
  260. //限制车高的范围,检验结果
  261. height=max_point.z;
  262. return SUCCESS;
  263. }
  264. void Locater::save_cloud_txt(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string save_file)
  265. {
  266. FILE* pfile=fopen(save_file.c_str(),"w");
  267. for(int i=0;i<cloud->size();++i)
  268. {
  269. fprintf(pfile,"%.3f %.3f %.3f\n",cloud->points[i].x,cloud->points[i].y,cloud->points[i].z);
  270. }
  271. fclose(pfile);
  272. }
  273. Error_manager Locater::locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_src,
  274. Locate_information& locate_information, std::string work_dir)
  275. {
  276. if(cloud_src.get()==0)
  277. {
  278. return Error_manager(LOCATER_INPUT_CLOUD_UNINIT,NORMAL,"locate input cloud is not init");
  279. }
  280. if(cloud_src->size()==0) {
  281. return Error_manager(LOCATER_INPUT_CLOUD_EMPTY,NORMAL,"input cloud is empty");
  282. }
  283. //10mm网格过滤
  284. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>);
  285. /// ///体素网格 下采样
  286. pcl::VoxelGrid<pcl::PointXYZ> vgfilter;
  287. vgfilter.setInputCloud(cloud_src);
  288. vgfilter.setLeafSize(30.f, 30.f, 30.f);
  289. vgfilter.filter(*cloud_in);
  290. //保存原始点云 src.txt
  291. std::string src_cloud_file=work_dir+"/src.txt";
  292. save_cloud_txt(cloud_in,src_cloud_file);
  293. //置初始结果为错误
  294. locate_information.locate_correct=false;
  295. Error_manager code;
  296. //第一步 yolo定位车辆外接矩形
  297. std::vector<YoloBox> t_yolo_boxes;
  298. code=locate_yolo(cloud_in,t_yolo_boxes,work_dir);
  299. if(code!=SUCCESS)
  300. {
  301. return code;
  302. }
  303. //第二步 ,根据yolo框结合PointSift识别车身点云,第0类即轮胎,第二类为车身
  304. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_wheel(new pcl::PointCloud<pcl::PointXYZ>);
  305. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car(new pcl::PointCloud<pcl::PointXYZ>);
  306. code=locate_sift(cloud_in,t_yolo_boxes,cloud_wheel,cloud_car,work_dir);
  307. if(code!=SUCCESS)
  308. {
  309. return code;
  310. }
  311. //第三步,计算车辆高度
  312. float height_car=0;
  313. code=measure_height(cloud_car,height_car);
  314. if(code!=SUCCESS)
  315. {
  316. return code;
  317. }
  318. locate_information.locate_hight=height_car;
  319. //第四步,识别轮胎,并根据轮胎数量计算旋转矩形
  320. float center_x;
  321. float center_y;
  322. float wheel_base;
  323. float width;
  324. float angle;
  325. code=locate_wheel(cloud_wheel,center_x,center_y,wheel_base,width,angle,work_dir);
  326. if(code!=SUCCESS)
  327. {
  328. return code;
  329. }
  330. //第六步,结果赋值
  331. //角度以度为单位
  332. locate_information.locate_x=center_x;
  333. locate_information.locate_y=center_y;
  334. locate_information.locate_theta = angle;
  335. locate_information.locate_length=wheel_base;
  336. locate_information.locate_width=width;
  337. locate_information.locate_hight=height_car;
  338. locate_information.locate_wheel_base=wheel_base;
  339. locate_information.locate_correct=true;
  340. LOG(INFO) << "Locate SUCCESS :" << " center:" << "[" << locate_information.locate_x
  341. << "," << locate_information.locate_y<< "] size= "
  342. << locate_information.locate_length << ", "
  343. << locate_information.locate_width << "," << locate_information.locate_hight
  344. << " angle=" << locate_information.locate_theta ;
  345. return SUCCESS;
  346. }