terminal_command_executor.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487
  1. #include "terminal_command_executor.h"
  2. #include <glog/logging.h>
  3. #include <chrono>
  4. #include <pcl/filters/passthrough.h>
  5. #include "../tool/pathcreator.h"
  6. ///增加获取wj电子围栏模块头文件
  7. #include "terminor_msg.pb.h"
  8. #include "MeasureRequest.h"
  9. //////以下两个函数用于测试,读取指定点云
  10. bool string2point(std::string str,pcl::PointXYZ& point)
  11. {
  12. std::istringstream iss;
  13. iss.str(str);
  14. float value;
  15. float data[3]={0};
  16. for(int i=0;i<3;++i)
  17. {
  18. if(iss>>value)
  19. {
  20. data[i]=value;
  21. }
  22. else
  23. {
  24. return false;
  25. }
  26. }
  27. point.x=data[0];
  28. point.y=data[1];
  29. point.z=data[2];
  30. return true;
  31. }
  32. pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
  33. {
  34. std::ifstream fin(file.c_str());
  35. const int line_length=64;
  36. char str[line_length]={0};
  37. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  38. while(fin.getline(str,line_length))
  39. {
  40. pcl::PointXYZ point;
  41. if(string2point(str,point))
  42. {
  43. cloud->push_back(point);
  44. }
  45. }
  46. return cloud;
  47. }
  48. //////////
  49. Terminor_Command_Executor::Terminor_Command_Executor(Terminal::Terminor_parameter parameter)
  50. :m_terminor_statu(TERMINOR_READY), mp_command_thread(0),m_timeout_second(15),mb_force_quit(false)
  51. {
  52. m_terminor_parameter=parameter;
  53. }
  54. Error_manager Terminor_Command_Executor::force_stop_command()
  55. {
  56. mb_force_quit=true;
  57. //等待执行线程退出
  58. if(mp_command_thread!=NULL)
  59. {
  60. if(mp_command_thread->joinable())
  61. {
  62. mp_command_thread->join();
  63. delete mp_command_thread;
  64. mp_command_thread=NULL;
  65. }
  66. }
  67. return SUCCESS;
  68. }
  69. Terminor_Command_Executor::~Terminor_Command_Executor()
  70. {
  71. if(mp_command_thread!=0)
  72. {
  73. force_stop_command();
  74. if(mp_command_thread->joinable())
  75. {
  76. mp_command_thread->join();
  77. delete mp_command_thread;
  78. mp_command_thread=0;
  79. }
  80. }
  81. }
  82. TerminorStatu Terminor_Command_Executor::get_terminor_statu()
  83. {
  84. return m_terminor_statu;
  85. }
  86. Error_manager Terminor_Command_Executor::execute_command(std::vector<Laser_base*> lasers,Plc_Communicator* plc,
  87. Locater* locater,Verify_result* verify_tool,float timeout)
  88. {
  89. Error_manager code;
  90. //第一步检查输入参数合法性
  91. for(int i=0;i<lasers.size();++i)
  92. {
  93. if(lasers[i]==0)
  94. {
  95. char description[255]={0};
  96. sprintf(description,"terminor input laser* is null index:%d, terminor id:%d",i,m_terminor_parameter.id());
  97. return Error_manager(TERMINOR_INPUT_LASER_NULL,NORMAL,description);
  98. }
  99. }
  100. if(plc==0)
  101. {
  102. char description[255]={0};
  103. sprintf(description,"terminor input plc* is null terminor id:%d",m_terminor_parameter.id());
  104. return Error_manager(TERMINOR_INPUT_PLC_NULL,NORMAL,description);
  105. }
  106. if(locater==0)
  107. {
  108. char description[255]={0};
  109. sprintf(description,"terminor input locater* is null terminor id:%d",m_terminor_parameter.id());
  110. return Error_manager(TERMINOR_INPUT_LOCATER_NULL,NORMAL,description);
  111. }
  112. mp_verify_tool=verify_tool;
  113. //第二步,雷达,plc以及定位模块是否能正常接收指令;
  114. for(int i=0;i<lasers.size();++i)
  115. {
  116. code=lasers[i]->check_error();
  117. if(code!=SUCCESS)
  118. {
  119. LOG(ERROR)<<" terminor check laser error:"<<code.to_string()<<" terminor id :"<<m_terminor_parameter.id();
  120. return code;
  121. }
  122. }
  123. //检查plc状态
  124. code=plc->get_error();
  125. if(code!=SUCCESS)
  126. {
  127. LOG(ERROR)<<"terminor check plc error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
  128. return code;
  129. }
  130. //检查测量模块状态
  131. code=locater->get_error();
  132. if(code!=SUCCESS)
  133. {
  134. LOG(ERROR)<<"terminor check locater error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
  135. return code;
  136. }
  137. // 检查当前终端指令执行器的状态是否空闲;如果空闲,进入测量流程,设置忙碌状态
  138. std::lock_guard<std::mutex> t_lock(m_mutex_lock);
  139. if(get_terminor_statu()!=TERMINOR_READY)
  140. {
  141. char description[255]={0};
  142. sprintf(description,"terminor is not ready, terminor id:%d",m_terminor_parameter.id());
  143. return Error_manager(TERMINOR_NOT_READY,NORMAL,description);
  144. }
  145. //检查上次线程是否退出,并等待线程退出
  146. if(mp_command_thread!=0)
  147. {
  148. if(mp_command_thread->joinable())
  149. {
  150. mp_command_thread->join();
  151. delete mp_command_thread;
  152. mp_command_thread=0;
  153. }
  154. }
  155. //第二步接受指令,保存输入参数,更新指令状态为TERMINOR_BUSY,启动内部工作线程.返回SUCCESS
  156. mp_laser_vector=lasers;
  157. mp_plc=plc;
  158. mp_locater=locater;
  159. m_terminor_statu=TERMINOR_BUSY;
  160. m_timeout_second=timeout;
  161. mp_command_thread=new std::thread(thread_command_working,this);
  162. if(mp_command_thread==0)
  163. {
  164. return Error_manager(TERMINOR_CREATE_WORKING_THREAD_FAILED,NORMAL,"terminor create thread failed");
  165. }
  166. return SUCCESS;
  167. }
  168. void Terminor_Command_Executor::thread_command_working(Terminor_Command_Executor* terminor)
  169. {
  170. if(terminor==NULL)
  171. {
  172. return ;
  173. }
  174. //执行指令,阻塞直到指令执行完成或者异常结束,此处如果失败,连续三次测量
  175. Error_manager code;
  176. int measure_times=0;
  177. while(terminor->mb_force_quit==false) {
  178. if (measure_times == 3)
  179. break;
  180. code = terminor->scanning_measuring();
  181. switch (code.get_error_code()) {
  182. case SUCCESS:
  183. break;
  184. case TERMINOR_LASER_TIMEOUT: {
  185. //雷达扫描超时,代表雷达故障,此时需要重置雷达模块
  186. }
  187. }
  188. if (code != SUCCESS ) {
  189. if(measure_times==2)
  190. {
  191. LOG(ERROR) << " Measure times("<<measure_times<<") failed : "<< code.to_string();
  192. }
  193. else
  194. {
  195. LOG(WARNING) << " Measure times("<<measure_times<<") failed : "<< code.to_string();
  196. }
  197. measure_times++;
  198. }
  199. else {
  200. LOG(INFO) << " Measure complete!!! times:"<<measure_times;
  201. break;
  202. }
  203. }
  204. //根据结果执行上传任务
  205. code=terminor->post_measure_information();
  206. //更新终端状态为Ready状态
  207. terminor->m_terminor_statu=TERMINOR_READY;
  208. if (code != SUCCESS) {
  209. LOG(ERROR) << "Command measure execute failed : "<< code.to_string();
  210. }
  211. else {
  212. LOG(INFO) << "Command execute complete!!!";
  213. }
  214. }
  215. /*
  216. * 执行上传plc任务
  217. */
  218. Error_manager Terminor_Command_Executor::post_measure_information()
  219. {
  220. //计时起点
  221. auto t_start_point=std::chrono::system_clock::now();
  222. Error_manager code;
  223. //执行plc上传任务
  224. m_terminor_statu=TERMINOR_POSTING;
  225. Plc_Task* plc_task=new Plc_Task();
  226. measure_result measure_information;
  227. measure_information.x=m_measure_information.locate_x;
  228. measure_information.y=m_measure_information.locate_y;
  229. measure_information.angle=m_measure_information.locate_theta;
  230. measure_information.length=m_measure_information.locate_length;
  231. measure_information.width=m_measure_information.locate_width;
  232. measure_information.height=m_measure_information.locate_hight;
  233. measure_information.wheel_base=m_measure_information.locate_wheel_base;
  234. //plc终端编号从1开始,因此,上传给plc的终端编号必须+1
  235. measure_information.terminal_id=m_terminor_parameter.id()+1;
  236. measure_information.correctness=m_measure_information.locate_correct;
  237. plc_task->set_result(measure_information);
  238. code=mp_plc->execute_task(plc_task);
  239. while(code!=SUCCESS)
  240. {
  241. //判断是否强制退出
  242. if(mb_force_quit==true)
  243. {
  244. char description[255]={0};
  245. sprintf(description,"ternimal is force quit terminal id : %d",m_terminor_parameter.id());
  246. return Error_manager(TERMINOR_FORCE_QUIT,NORMAL,description);
  247. }
  248. //对于上传不成功,作失败处理,重新传输
  249. code=mp_plc->execute_task(plc_task);
  250. ///不成功,检测本次流程是否超时
  251. if(code!=SUCCESS)
  252. {
  253. auto t_end_point=std::chrono::system_clock::now();
  254. auto duration=std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
  255. double second=double(duration.count()) *
  256. std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
  257. if(second>m_timeout_second)
  258. {
  259. //扫描超时处理
  260. return Error_manager(TERMINOR_POST_PLC_TIMEOUT,NORMAL,"post plc timeout");
  261. }
  262. usleep(1000*100);
  263. }
  264. }
  265. return code;
  266. }
  267. void Terminor_Command_Executor::set_save_root_path(std::string root)
  268. {
  269. m_save_root_path=root;
  270. }
  271. Error_manager Terminor_Command_Executor::scanning_measuring()
  272. {
  273. //计时起点
  274. auto t_start_point=std::chrono::system_clock::now();
  275. //准备目录
  276. time_t tt;
  277. time( &tt );
  278. tt = tt + 8*3600; // transform the time zone
  279. tm* t= gmtime( &tt );
  280. char path[255]={0};
  281. sprintf(path,"%s/%4d/%02d/%02d",m_save_root_path.c_str(),
  282. t->tm_year + 1900,
  283. t->tm_mon + 1,
  284. t->tm_mday);
  285. PathCreator path_creator;
  286. path_creator.CreateDatePath(path);
  287. std::string project_path;
  288. path_creator.GetCurPath(project_path);
  289. Error_manager code;
  290. //第一步,启动雷达扫描点云,切换当前状态为扫描中
  291. //根据配置筛选雷达
  292. pcl::PointCloud<pcl::PointXYZ>::Ptr scan_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  293. std::mutex cloud_lock;
  294. std::vector<Task_Base*> laser_task_vector;
  295. std::vector<Laser_base*> tp_lasers;
  296. for(int i=0;i<m_terminor_parameter.laser_parameter_size();++i)
  297. {
  298. int laser_id=m_terminor_parameter.laser_parameter(i).id();
  299. int frame_count=m_terminor_parameter.laser_parameter(i).frame_count();
  300. if(frame_count<=0)
  301. {
  302. LOG(WARNING)<<"terminal parameter laser["<<laser_id<<"] frame count is <0";
  303. continue;
  304. }
  305. if(laser_id>=0&&laser_id<mp_laser_vector.size())
  306. {
  307. //判断该id的雷达是否已经添加进去, 放置配置中出现重复的雷达编号
  308. bool tb_repeat=false;
  309. for(int j=0;j<tp_lasers.size();++j)
  310. {
  311. if(tp_lasers[j]==mp_laser_vector[laser_id])
  312. {
  313. tb_repeat=true;
  314. break;
  315. }
  316. }
  317. if(tb_repeat==false)
  318. {
  319. tp_lasers.push_back(mp_laser_vector[laser_id]);
  320. //创建扫描任务,
  321. Laser_task* laser_task=new Laser_task();
  322. //
  323. laser_task->task_init(TASK_CREATED,scan_cloud,&cloud_lock);
  324. laser_task->set_task_points_number(frame_count);
  325. laser_task->set_save_path(project_path);
  326. laser_task_vector.push_back(laser_task);
  327. //发送任务单给雷达
  328. code=tp_lasers[i]->execute_task(laser_task);
  329. if(code!=SUCCESS)
  330. {
  331. return code;
  332. }
  333. }
  334. }
  335. }
  336. if(tp_lasers.size()==0)
  337. {
  338. return Error_manager(TERMINOR_NOT_CONTAINS_LASER,NORMAL,"terminal not contains laser");
  339. }
  340. m_terminor_statu=TERMINOR_SCANNING;
  341. //等待雷达完成任务单
  342. while(1)
  343. {
  344. //判断是否强制退出
  345. if(mb_force_quit==true)
  346. {
  347. char description[255]={0};
  348. sprintf(description,"ternimal is force quit terminal id : %d",m_terminor_parameter.id());
  349. return Error_manager(TERMINOR_FORCE_QUIT,NORMAL,description);
  350. }
  351. //判断雷达任务单是否全部完成
  352. bool tb_laser_complete=true;
  353. for(int i=0;i<laser_task_vector.size();++i)
  354. {
  355. tb_laser_complete &=(TASK_OVER==laser_task_vector[i]->get_statu());
  356. }
  357. if(tb_laser_complete)
  358. {
  359. break;
  360. }
  361. //计算扫描时间,若超时,并且没有点,则返回错误.
  362. auto t_end_point=std::chrono::system_clock::now();
  363. auto duration=std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
  364. double second=double(duration.count()) *
  365. std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
  366. if(second>m_timeout_second)
  367. {
  368. //扫描超时,点云中没有点,则返回错误
  369. if(scan_cloud->size()==0)
  370. {
  371. return Error_manager(TERMINOR_LASER_TIMEOUT,MAJOR_ERROR,"laser scanning timeout");
  372. }
  373. }
  374. usleep(1000*100);
  375. }
  376. //检查雷达任务完成情况,是否是正常完成
  377. LOG(INFO)<<" laser scanning over cloud size:"<<scan_cloud->size();
  378. //释放扫描任务单
  379. for(int i=0;i<laser_task_vector.size();++i)
  380. {
  381. if(laser_task_vector[i]!=0)
  382. {
  383. delete laser_task_vector[i];
  384. laser_task_vector[i]=NULL;
  385. }
  386. }
  387. //第二步,根据区域筛选点云
  388. pcl::PointCloud<pcl::PointXYZ>::Ptr locate_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  389. pcl::PassThrough<pcl::PointXYZ> passX;
  390. pcl::PassThrough<pcl::PointXYZ> passY;
  391. pcl::PassThrough<pcl::PointXYZ> passZ;
  392. passX.setInputCloud(scan_cloud);
  393. passX.setFilterFieldName("x");
  394. passX.setFilterLimits(m_terminor_parameter.area_3d().min_x(),m_terminor_parameter.area_3d().max_x());
  395. passX.filter(*locate_cloud);
  396. passY.setInputCloud(locate_cloud);
  397. passY.setFilterFieldName("y");
  398. passY.setFilterLimits(m_terminor_parameter.area_3d().min_y(),m_terminor_parameter.area_3d().max_y());
  399. passY.filter(*locate_cloud);
  400. passY.setInputCloud(locate_cloud);
  401. passY.setFilterFieldName("z");
  402. passY.setFilterLimits(m_terminor_parameter.area_3d().min_z(),m_terminor_parameter.area_3d().max_z());
  403. passY.filter(*locate_cloud);
  404. LOG(INFO)<<"筛选点云点数 : "<<locate_cloud->size();
  405. //第三步,创建测量任务, 进入测量中
  406. Locate_task* locate_task=new Locate_task();
  407. locate_task->set_locate_cloud(locate_cloud);
  408. locate_task->set_save_path(project_path);
  409. m_terminor_statu=TERMINOR_MEASURING;
  410. code=mp_locater->execute_task(locate_task);
  411. //获取测量结果
  412. m_measure_information=locate_task->get_locate_information();
  413. if(code!=SUCCESS)
  414. {
  415. m_measure_information.locate_correct=false;
  416. //对于失败情况,获取wj电子围栏结果
  417. MeasureRequest requst("tcp://127.0.0.1:9000");
  418. std::string response;
  419. char cmd[255] = {0};
  420. sprintf(cmd, "Terminal%d", m_terminor_parameter.id());
  421. if (requst.Request(cmd, response)) {
  422. Terminal::wj_locate_information wj_infomation;
  423. wj_infomation.ParseFromString(response);
  424. m_measure_information.locate_theta = wj_infomation.c();
  425. m_measure_information.locate_correct = wj_infomation.correctness();
  426. m_measure_information.locate_width = wj_infomation.width();
  427. m_measure_information.locate_x = wj_infomation.x();
  428. m_measure_information.locate_y = wj_infomation.y();
  429. m_measure_information.locate_wheel_base = wj_infomation.wheel_base();
  430. LOG(INFO) << "locate from WJ-defence :\n" << wj_infomation.DebugString();
  431. if(wj_infomation.correctness())
  432. code=SUCCESS;
  433. }
  434. }
  435. //释放locate task
  436. if(locate_task!=NULL)
  437. {
  438. delete locate_task;
  439. locate_task=NULL;
  440. }
  441. ////如果测量正确,检验结果
  442. if(mp_verify_tool!=NULL)
  443. {
  444. if (code == SUCCESS)
  445. {
  446. cv::RotatedRect rotated_rect;
  447. rotated_rect.center = cv::Point2f(m_measure_information.locate_x, m_measure_information.locate_y);
  448. rotated_rect.angle = m_measure_information.locate_theta;
  449. if (m_measure_information.locate_theta > 0 && m_measure_information.locate_theta <= 90) {
  450. rotated_rect.size.height = m_measure_information.locate_length;
  451. rotated_rect.size.width = m_measure_information.locate_width;
  452. }
  453. else {
  454. rotated_rect.size.height = m_measure_information.locate_width;
  455. rotated_rect.size.width = m_measure_information.locate_length;
  456. }
  457. code=mp_verify_tool->verify(rotated_rect,false);
  458. return code;
  459. }
  460. }
  461. return code;
  462. }