terminal_command_executor.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420
  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,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. //第二步,雷达,plc以及定位模块是否能正常接收指令;
  113. for(int i=0;i<lasers.size();++i)
  114. {
  115. code=lasers[i]->check_error();
  116. if(code!=SUCCESS)
  117. {
  118. LOG(ERROR)<<" terminor check laser error:"<<code.to_string()<<" terminor id :"<<m_terminor_parameter.id();
  119. return code;
  120. }
  121. }
  122. //检查plc状态
  123. code=plc->get_error();
  124. if(code!=SUCCESS)
  125. {
  126. LOG(ERROR)<<"terminor check plc error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
  127. return code;
  128. }
  129. //检查测量模块状态
  130. code=locater->get_error();
  131. if(code!=SUCCESS)
  132. {
  133. LOG(ERROR)<<"terminor check locater error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
  134. return code;
  135. }
  136. // 检查当前终端指令执行器的状态是否空闲;如果空闲,进入测量流程,设置忙碌状态
  137. std::lock_guard<std::mutex> t_lock(m_mutex_lock);
  138. if(get_terminor_statu()!=TERMINOR_READY)
  139. {
  140. char description[255]={0};
  141. sprintf(description,"terminor is not ready, terminor id:%d",m_terminor_parameter.id());
  142. return Error_manager(TERMINOR_NOT_READY,NORMAL,description);
  143. }
  144. //检查上次线程是否退出,并等待线程退出
  145. if(mp_command_thread!=0)
  146. {
  147. if(mp_command_thread->joinable())
  148. {
  149. mp_command_thread->join();
  150. delete mp_command_thread;
  151. mp_command_thread=0;
  152. }
  153. }
  154. //第二步接受指令,保存输入参数,更新指令状态为,启动内部工作线程.返回SUCCESS
  155. mp_laser_vector=lasers;
  156. mp_plc=plc;
  157. mp_locater=locater;
  158. m_terminor_statu=TERMINOR_BUSY;
  159. m_timeout_second=timeout;
  160. mp_command_thread=new std::thread(thread_command_working,this);
  161. if(mp_command_thread==0)
  162. {
  163. return Error_manager(TERMINOR_CREATE_WORKING_THREAD_FAILED,NORMAL,"terminor create thread failed");
  164. }
  165. return SUCCESS;
  166. }
  167. void Terminor_Command_Executor::thread_command_working(Terminor_Command_Executor* terminor)
  168. {
  169. if(terminor==NULL)
  170. {
  171. return ;
  172. }
  173. //执行指令,阻塞直到指令执行完成或者异常结束
  174. Error_manager code=terminor->scanning_measuring();
  175. switch(code.get_error_code())
  176. {
  177. case SUCCESS:break;
  178. case TERMINOR_LASER_TIMEOUT:
  179. {
  180. //雷达扫描超时,代表雷达故障,此时需要重置雷达模块
  181. }
  182. }
  183. if(code!=SUCCESS)
  184. {
  185. LOG(ERROR)<<"Command execute failed : "<<code.to_string();
  186. }
  187. //根据结果执行上传任务
  188. code=terminor->post_measure_information();
  189. //更新终端状态为Ready状态
  190. terminor->m_terminor_statu=TERMINOR_READY;
  191. if(code!=SUCCESS)
  192. {
  193. LOG(ERROR)<<"Command execute failed : "<<code.to_string();
  194. }
  195. else
  196. {
  197. LOG(INFO)<<"Command execute complete!!!";
  198. }
  199. }
  200. /*
  201. * 执行上传plc任务
  202. */
  203. Error_manager Terminor_Command_Executor::post_measure_information()
  204. {
  205. //计时起点
  206. auto t_start_point=std::chrono::system_clock::now();
  207. Error_manager code;
  208. //执行plc上传任务
  209. m_terminor_statu=TERMINOR_POSTING;
  210. Plc_Task* plc_task=new Plc_Task();
  211. measure_result measure_information;
  212. measure_information.x=m_measure_information.locate_x;
  213. measure_information.y=m_measure_information.locate_y;
  214. measure_information.angle=m_measure_information.locate_theta;
  215. measure_information.length=m_measure_information.locate_length;
  216. measure_information.width=m_measure_information.locate_width;
  217. measure_information.height=m_measure_information.locate_hight;
  218. measure_information.wheel_base=m_measure_information.locate_wheel_base;
  219. //plc终端编号从1开始,因此,上传给plc的终端编号必须+1
  220. measure_information.terminal_id=m_terminor_parameter.id()+1;
  221. measure_information.correctness=m_measure_information.locate_correct;
  222. plc_task->set_result(measure_information);
  223. code=mp_plc->execute_task(plc_task);
  224. while(code!=SUCCESS)
  225. {
  226. //判断是否强制退出
  227. if(mb_force_quit==true)
  228. {
  229. char description[255]={0};
  230. sprintf(description,"ternimal is force quit terminal id : %d",m_terminor_parameter.id());
  231. return Error_manager(TERMINOR_FORCE_QUIT,NORMAL,description);
  232. }
  233. //对于上传不成功,作失败处理,重新传输
  234. code=mp_plc->execute_task(plc_task);
  235. ///不成功,检测本次流程是否超时
  236. if(code!=SUCCESS)
  237. {
  238. auto t_end_point=std::chrono::system_clock::now();
  239. auto duration=std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
  240. double second=double(duration.count()) *
  241. std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
  242. if(second>m_timeout_second)
  243. {
  244. //扫描超时处理
  245. return Error_manager(TERMINOR_POST_PLC_TIMEOUT,NORMAL,"post plc timeout");
  246. }
  247. usleep(1000*100);
  248. }
  249. }
  250. return code;
  251. }
  252. void Terminor_Command_Executor::set_save_root_path(std::string root)
  253. {
  254. m_save_root_path=root;
  255. }
  256. Error_manager Terminor_Command_Executor::scanning_measuring()
  257. {
  258. //计时起点
  259. auto t_start_point=std::chrono::system_clock::now();
  260. //准备目录
  261. time_t tt;
  262. time( &tt );
  263. tt = tt + 8*3600; // transform the time zone
  264. tm* t= gmtime( &tt );
  265. char path[255]={0};
  266. sprintf(path,"%s/%4d/%02d/%02d",m_save_root_path.c_str(),
  267. t->tm_year + 1900,
  268. t->tm_mon + 1,
  269. t->tm_mday);
  270. PathCreator path_creator;
  271. path_creator.CreateDatePath(path);
  272. std::string project_path;
  273. path_creator.GetCurPath(project_path);
  274. Error_manager code;
  275. //第一步,启动雷达扫描点云,切换当前状态为扫描中
  276. pcl::PointCloud<pcl::PointXYZ>::Ptr scan_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  277. std::mutex cloud_lock;
  278. std::vector<Task_Base*> laser_task_vector;
  279. for(int i=0;i<mp_laser_vector.size();++i)
  280. {
  281. Laser_task* laser_task=new Laser_task();
  282. //
  283. laser_task->task_init(TASK_CREATED,scan_cloud,&cloud_lock);
  284. laser_task->set_task_points_number(1000);
  285. laser_task->set_save_path(project_path);
  286. laser_task_vector.push_back(laser_task);
  287. //发送任务单给雷达
  288. code=mp_laser_vector[i]->execute_task(laser_task);
  289. if(code!=SUCCESS)
  290. {
  291. return code;
  292. }
  293. }
  294. m_terminor_statu=TERMINOR_SCANNING;
  295. //等待雷达完成任务单
  296. while(1)
  297. {
  298. //判断是否强制退出
  299. if(mb_force_quit==true)
  300. {
  301. char description[255]={0};
  302. sprintf(description,"ternimal is force quit terminal id : %d",m_terminor_parameter.id());
  303. return Error_manager(TERMINOR_FORCE_QUIT,NORMAL,description);
  304. }
  305. //判断雷达任务单是否全部完成
  306. bool tb_laser_complete=true;
  307. for(int i=0;i<laser_task_vector.size();++i)
  308. {
  309. tb_laser_complete &=(TASK_OVER==laser_task_vector[i]->get_statu());
  310. }
  311. if(tb_laser_complete)
  312. {
  313. break;
  314. }
  315. //计算扫描时间,若超时,并且没有点,则返回错误.
  316. auto t_end_point=std::chrono::system_clock::now();
  317. auto duration=std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
  318. double second=double(duration.count()) *
  319. std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
  320. if(second>m_timeout_second)
  321. {
  322. //扫描超时,点云中没有点,则返回错误
  323. if(scan_cloud->size()==0)
  324. {
  325. return Error_manager(TERMINOR_LASER_TIMEOUT,MAJOR_ERROR,"laser scanning timeout");
  326. }
  327. }
  328. usleep(1000*100);
  329. }
  330. //检查雷达任务完成情况,是否是正常完成
  331. LOG(INFO)<<" laser scanning over cloud size:"<<scan_cloud->size();
  332. //释放扫描任务单
  333. for(int i=0;i<laser_task_vector.size();++i)
  334. {
  335. if(laser_task_vector[i]!=0)
  336. {
  337. delete laser_task_vector[i];
  338. laser_task_vector[i]=NULL;
  339. }
  340. }
  341. //第二步,根据区域筛选点云
  342. pcl::PointCloud<pcl::PointXYZ>::Ptr locate_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  343. pcl::PassThrough<pcl::PointXYZ> passX;
  344. pcl::PassThrough<pcl::PointXYZ> passY;
  345. pcl::PassThrough<pcl::PointXYZ> passZ;
  346. passX.setInputCloud(scan_cloud);
  347. passX.setFilterFieldName("x");
  348. passX.setFilterLimits(m_terminor_parameter.area_3d().min_x(),m_terminor_parameter.area_3d().max_x());
  349. passX.filter(*locate_cloud);
  350. passY.setInputCloud(locate_cloud);
  351. passY.setFilterFieldName("y");
  352. passY.setFilterLimits(m_terminor_parameter.area_3d().min_y(),m_terminor_parameter.area_3d().max_y());
  353. passY.filter(*locate_cloud);
  354. passY.setInputCloud(locate_cloud);
  355. passY.setFilterFieldName("z");
  356. passY.setFilterLimits(m_terminor_parameter.area_3d().min_z(),m_terminor_parameter.area_3d().max_z());
  357. passY.filter(*locate_cloud);
  358. LOG(INFO)<<"筛选点云点数 : "<<locate_cloud->size();
  359. //第三步,创建测量任务, 进入测量中
  360. Locate_task* locate_task=new Locate_task();
  361. locate_task->set_locate_cloud(locate_cloud);
  362. locate_task->set_save_path(project_path);
  363. m_terminor_statu=TERMINOR_MEASURING;
  364. code=mp_locater->execute_task(locate_task);
  365. //获取测量结果
  366. m_measure_information=locate_task->get_locate_information();
  367. if(code!=SUCCESS)
  368. {
  369. m_measure_information.locate_correct=false;
  370. //对于失败情况,获取wj电子围栏结果
  371. MeasureRequest requst("tcp://127.0.0.1:9000");
  372. std::string response;
  373. char cmd[255] = {0};
  374. sprintf(cmd, "Terminal%d", m_terminor_parameter.id());
  375. if (requst.Request(cmd, response)) {
  376. Terminal::wj_locate_information wj_infomation;
  377. wj_infomation.ParseFromString(response);
  378. m_measure_information.locate_theta = wj_infomation.c();
  379. m_measure_information.locate_correct = wj_infomation.correctness();
  380. m_measure_information.locate_width = wj_infomation.width();
  381. m_measure_information.locate_x = wj_infomation.x();
  382. m_measure_information.locate_y = wj_infomation.y();
  383. m_measure_information.locate_wheel_base = wj_infomation.wheel_base();
  384. LOG(INFO) << "locate from WJ-defence :\n" << wj_infomation.DebugString();
  385. if(wj_infomation.correctness())
  386. code=SUCCESS;
  387. }
  388. }
  389. //释放locate task
  390. if(locate_task!=NULL)
  391. {
  392. delete locate_task;
  393. locate_task=NULL;
  394. }
  395. return code;
  396. }