terminal_command_executor.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601
  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. std::mutex Terminor_Command_Executor::ms_mutex_scan_measure;
  10. //////以下两个函数用于测试,读取指定点云
  11. bool string2point(std::string str,pcl::PointXYZ& point)
  12. {
  13. std::istringstream iss;
  14. iss.str(str);
  15. float value;
  16. float data[3]={0};
  17. for(int i=0;i<3;++i)
  18. {
  19. if(iss>>value)
  20. {
  21. data[i]=value;
  22. }
  23. else
  24. {
  25. return false;
  26. }
  27. }
  28. point.x=data[0];
  29. point.y=data[1];
  30. point.z=data[2];
  31. return true;
  32. }
  33. pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
  34. {
  35. std::ifstream fin(file.c_str());
  36. const int line_length=64;
  37. char str[line_length]={0};
  38. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  39. while(fin.getline(str,line_length))
  40. {
  41. pcl::PointXYZ point;
  42. if(string2point(str,point))
  43. {
  44. cloud->push_back(point);
  45. }
  46. }
  47. return cloud;
  48. }
  49. //////////
  50. Terminor_Command_Executor::Terminor_Command_Executor(Terminal::Terminor_parameter parameter)
  51. :m_terminor_statu(TERMINOR_READY), mp_command_thread(0),m_timeout_second(15),mb_force_quit(false)
  52. {
  53. m_terminor_parameter=parameter;
  54. mp_wj_lidar=NULL;
  55. }
  56. Error_manager Terminor_Command_Executor::force_stop_command()
  57. {
  58. mb_force_quit=true;
  59. //等待执行线程退出
  60. if(mp_command_thread!=NULL)
  61. {
  62. if(mp_command_thread->joinable())
  63. {
  64. mp_command_thread->join();
  65. delete mp_command_thread;
  66. mp_command_thread=NULL;
  67. }
  68. }
  69. return SUCCESS;
  70. }
  71. Terminor_Command_Executor::~Terminor_Command_Executor()
  72. {
  73. if(mp_command_thread!=0)
  74. {
  75. force_stop_command();
  76. if(mp_command_thread->joinable())
  77. {
  78. mp_command_thread->join();
  79. delete mp_command_thread;
  80. mp_command_thread=0;
  81. }
  82. }
  83. }
  84. TerminorStatu Terminor_Command_Executor::get_terminor_statu()
  85. {
  86. return m_terminor_statu;
  87. }
  88. Error_manager Terminor_Command_Executor::execute_command(std::vector<Laser_base*> lasers,Fence_controller* wj_lidar,
  89. Plc_Communicator* plc,Locater* locater,Verify_result* verify_tool,float timeout)
  90. {
  91. Error_manager code;
  92. //第一步检查输入参数合法性
  93. for(int i=0;i<lasers.size();++i)
  94. {
  95. if(lasers[i]==0)
  96. {
  97. char description[255]={0};
  98. sprintf(description,"terminor input laser* is null index:%d, terminor id:%d",i,m_terminor_parameter.id());
  99. return Error_manager(TERMINOR_INPUT_LASER_NULL,NORMAL,description);
  100. }
  101. }
  102. if(plc==0)
  103. {
  104. char description[255]={0};
  105. sprintf(description,"terminor input plc* is null terminor id:%d",m_terminor_parameter.id());
  106. return Error_manager(TERMINOR_INPUT_PLC_NULL,NORMAL,description);
  107. }
  108. if(wj_lidar==NULL)
  109. {
  110. char description[255]={0};
  111. sprintf(description,"terminor input wj_lidar* is null terminor id:%d",m_terminor_parameter.id());
  112. return Error_manager(TERMINOR_INPUT_LOCATER_NULL,NORMAL,description);
  113. }
  114. if(locater==0)
  115. {
  116. char description[255]={0};
  117. sprintf(description,"terminor input locater* is null terminor id:%d",m_terminor_parameter.id());
  118. return Error_manager(TERMINOR_INPUT_LOCATER_NULL,NORMAL,description);
  119. }
  120. mp_verify_tool=verify_tool;
  121. //第二步,雷达,plc以及定位模块是否能正常接收指令;
  122. for(int i=0;i<lasers.size();++i)
  123. {
  124. code=lasers[i]->check_laser();
  125. if(code!=SUCCESS)
  126. {
  127. LOG(ERROR)<<" terminor check laser error:"<<code.to_string()<<" terminor id :"<<m_terminor_parameter.id();
  128. return code;
  129. }
  130. }
  131. //检查plc状态
  132. code=plc->get_error();
  133. if(code!=SUCCESS)
  134. {
  135. LOG(ERROR)<<"terminor check plc error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
  136. return code;
  137. }
  138. //检查测量模块状态
  139. code=locater->get_error();
  140. if(code!=SUCCESS)
  141. {
  142. LOG(ERROR)<<"terminor check locater error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
  143. return code;
  144. }
  145. // 检查当前终端指令执行器的状态是否空闲;如果空闲,进入测量流程,设置忙碌状态
  146. std::lock_guard<std::mutex> t_lock(m_mutex_lock);
  147. if(get_terminor_statu()!=TERMINOR_READY)
  148. {
  149. char description[255]={0};
  150. sprintf(description,"terminor is not ready, terminor id:%d",m_terminor_parameter.id());
  151. return Error_manager(TERMINOR_NOT_READY,NORMAL,description);
  152. }
  153. //检查上次线程是否退出,并等待线程退出
  154. if(mp_command_thread!=0)
  155. {
  156. if(mp_command_thread->joinable())
  157. {
  158. mp_command_thread->join();
  159. delete mp_command_thread;
  160. mp_command_thread=0;
  161. }
  162. }
  163. //第二步接受指令,保存输入参数,更新指令状态为TERMINOR_BUSY,启动内部工作线程.返回SUCCESS
  164. mp_laser_vector=lasers;
  165. mp_plc=plc;
  166. mp_wj_lidar=wj_lidar;
  167. mp_locater=locater;
  168. m_terminor_statu=TERMINOR_BUSY;
  169. m_timeout_second=timeout;
  170. mp_command_thread=new std::thread(thread_command_working,this);
  171. if(mp_command_thread==0)
  172. {
  173. return Error_manager(TERMINOR_CREATE_WORKING_THREAD_FAILED,NORMAL,"terminor create thread failed");
  174. }
  175. return SUCCESS;
  176. }
  177. void Terminor_Command_Executor::thread_command_working(Terminor_Command_Executor* terminor)
  178. {
  179. if(terminor==NULL)
  180. {
  181. return ;
  182. }
  183. //执行指令,阻塞直到指令执行完成或者异常结束,此处如果失败,连续三次测量
  184. Error_manager code;
  185. int measure_times=0;
  186. while(terminor->mb_force_quit==false) {
  187. if (measure_times == 3)
  188. break;
  189. code = terminor->scanning_measuring();
  190. switch (code.get_error_code()) {
  191. case SUCCESS:
  192. break;
  193. case TERMINOR_LASER_TIMEOUT: {
  194. //雷达扫描超时,代表雷达故障,此时需要重置雷达模块
  195. }
  196. }
  197. if (code != SUCCESS ) {
  198. if(measure_times==2)
  199. {
  200. LOG(ERROR) << " Measure times("<<measure_times<<") failed : "<< code.to_string();
  201. }
  202. else
  203. {
  204. LOG(WARNING) << " Measure times("<<measure_times<<") failed : "<< code.to_string();
  205. }
  206. measure_times++;
  207. }
  208. else {
  209. LOG(INFO) << " Measure complete!!! times:"<<measure_times;
  210. break;
  211. }
  212. }
  213. //根据结果执行上传任务
  214. code=terminor->post_measure_information();
  215. //更新终端状态为Ready状态
  216. terminor->m_terminor_statu=TERMINOR_READY;
  217. if (code != SUCCESS) {
  218. LOG(ERROR) << "Command measure execute failed : "<< code.to_string();
  219. }
  220. else {
  221. LOG(INFO) << "Command execute complete!!!";
  222. }
  223. }
  224. /*
  225. * 执行上传plc任务
  226. */
  227. Error_manager Terminor_Command_Executor::post_measure_information()
  228. {
  229. //计时起点
  230. auto t_start_point=std::chrono::system_clock::now();
  231. Error_manager code;
  232. //执行plc上传任务
  233. m_terminor_statu=TERMINOR_POSTING;
  234. Plc_Task* plc_task=new Plc_Task();
  235. measure_result measure_information;
  236. measure_information.x=m_measure_information.locate_x;
  237. measure_information.y=m_measure_information.locate_y;
  238. measure_information.angle=m_measure_information.locate_theta;
  239. measure_information.length=m_measure_information.locate_length;
  240. measure_information.width=m_measure_information.locate_width;
  241. measure_information.height=m_measure_information.locate_hight;
  242. measure_information.wheel_base=m_measure_information.locate_wheel_base;
  243. //plc终端编号从1开始,因此,上传给plc的终端编号必须+1
  244. measure_information.terminal_id=m_terminor_parameter.id()+1;
  245. measure_information.correctness=m_measure_information.locate_correct;
  246. plc_task->set_result(measure_information);
  247. code=mp_plc->execute_task(plc_task);
  248. while(code!=SUCCESS)
  249. {
  250. //判断是否强制退出
  251. if(mb_force_quit==true)
  252. {
  253. char description[255]={0};
  254. sprintf(description,"ternimal is force quit terminal id : %d",m_terminor_parameter.id());
  255. return Error_manager(TERMINOR_FORCE_QUIT,NORMAL,description);
  256. }
  257. //对于上传不成功,作失败处理,重新传输
  258. code=mp_plc->execute_task(plc_task);
  259. ///不成功,检测本次流程是否超时
  260. if(code!=SUCCESS)
  261. {
  262. auto t_end_point=std::chrono::system_clock::now();
  263. auto duration=std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
  264. double second=double(duration.count()) *
  265. std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
  266. if(second>m_timeout_second)
  267. {
  268. //扫描超时处理
  269. return Error_manager(TERMINOR_POST_PLC_TIMEOUT,NORMAL,"post plc timeout");
  270. }
  271. usleep(1000*100);
  272. }
  273. }
  274. return code;
  275. }
  276. void Terminor_Command_Executor::set_save_root_path(std::string root)
  277. {
  278. m_save_root_path=root;
  279. }
  280. Error_manager Terminor_Command_Executor::scanning_measuring() {
  281. std::lock_guard<std::mutex> lock(ms_mutex_scan_measure);
  282. Error_manager code;
  283. Error_manager t_result;
  284. LOG(INFO) << ">>>>>>>>>>>> Enter terminator ID:" << m_terminor_parameter.id();
  285. //计时起点
  286. auto t_start_point = std::chrono::system_clock::now();
  287. //准备目录
  288. time_t tt;
  289. time(&tt);
  290. tt = tt + 8 * 3600; // transform the time zone
  291. tm *t = gmtime(&tt);
  292. char path[255] = {0};
  293. sprintf(path, "%s/%4d/%02d/%02d", m_save_root_path.c_str(),
  294. t->tm_year + 1900,
  295. t->tm_mon + 1,
  296. t->tm_mday);
  297. PathCreator path_creator;
  298. path_creator.CreateDatePath(path);
  299. std::string project_path = path_creator.GetCurPath();
  300. //第一步,启动雷达扫描点云,切换当前状态为扫描中
  301. //根据配置筛选雷达
  302. pcl::PointCloud<pcl::PointXYZ> scan_cloud;
  303. std::mutex cloud_lock;
  304. std::vector<Laser_task *> laser_task_vector;
  305. std::vector<Laser_base *> tp_lasers;
  306. for (int i = 0; i < m_terminor_parameter.laser_parameter_size(); ++i) {
  307. int laser_id = m_terminor_parameter.laser_parameter(i).id();
  308. int frame_count = m_terminor_parameter.laser_parameter(i).frame_count();
  309. if (frame_count <= 0) {
  310. LOG(WARNING) << "terminal parameter laser[" << laser_id << "] frame count is <0";
  311. continue;
  312. }
  313. if (laser_id >= 0 && laser_id < mp_laser_vector.size()) {
  314. //判断该id的雷达是否已经添加进去, 放置配置中出现重复的雷达编号
  315. bool tb_repeat = false;
  316. for (int j = 0; j < tp_lasers.size(); ++j) {
  317. if (tp_lasers[j] == mp_laser_vector[laser_id]) {
  318. tb_repeat = true;
  319. break;
  320. }
  321. }
  322. if (tb_repeat == false) {
  323. tp_lasers.push_back(mp_laser_vector[laser_id]);
  324. //创建扫描任务,
  325. Laser_task *laser_task = new Laser_task();
  326. //
  327. laser_task->task_init(TASK_CREATED, &scan_cloud, &cloud_lock);
  328. laser_task->set_task_frame_maxnum(frame_count);
  329. laser_task->set_save_path(project_path);
  330. laser_task_vector.push_back(laser_task);
  331. //发送任务单给雷达
  332. code = tp_lasers[i]->execute_task(laser_task);
  333. if (code != SUCCESS) {
  334. return code;
  335. }
  336. }
  337. }
  338. }
  339. if (tp_lasers.size() == 0) {
  340. return Error_manager(TERMINOR_NOT_CONTAINS_LASER, NORMAL, "terminal not contains laser");
  341. }
  342. m_terminor_statu = TERMINOR_SCANNING;
  343. //等待雷达完成任务单
  344. while (1)
  345. {
  346. //判断是否强制退出
  347. if (mb_force_quit == true) {
  348. char description[255] = {0};
  349. sprintf(description, "ternimal is force quit terminal id : %d", m_terminor_parameter.id());
  350. return Error_manager(TERMINOR_FORCE_QUIT, NORMAL, description);
  351. }
  352. int i = 0;
  353. for (; i < laser_task_vector.size(); ++i)
  354. {
  355. if (laser_task_vector[i]->is_task_end() == false)
  356. {
  357. if (laser_task_vector[i]->is_over_time())
  358. {
  359. //超时处理。取消任务。
  360. tp_lasers[i]->cancel_task();
  361. laser_task_vector[i]->set_task_statu(TASK_DEAD);
  362. code.error_manager_reset(Error_code::LASER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  363. " LASER_TASK is_over_time ");
  364. laser_task_vector[i]->set_task_error_manager(code);
  365. continue;
  366. //本次子任务超时死亡.直接进行下一个
  367. }
  368. else
  369. {
  370. //如果任务还在执行, 那就等待任务继续完成,等1ms
  371. //std::this_thread::sleep_for(std::chrono::milliseconds(1));
  372. std::this_thread::yield();
  373. break;
  374. //注意了:这里break之后, i != laser_task_vector.size()
  375. //这就表示仍然有子任务单没有结束.那就继续等待,,,直到所有任务完成或者超时.
  376. }
  377. }
  378. //else 任务完成就判断下一个
  379. }
  380. //如果下发的任务全部结束,那么汇总所有的结果, 并销毁下发的任务单。
  381. if(i == laser_task_vector.size() )
  382. {
  383. for ( int j = 0; j < laser_task_vector.size(); ++j)
  384. {
  385. if (laser_task_vector[i] != NULL) {
  386. //数据汇总,
  387. //由于 pcl::PointCloud<pcl::PointXYZ>::Ptr mp_task_point_cloud; 是所有任务单共用的,所以不用处理了。自动就在一起。
  388. //错误汇总
  389. t_result.compare_and_cover_error(laser_task_vector[j]->get_task_error_manager());
  390. //销毁下发的任务单。
  391. delete laser_task_vector[j];
  392. laser_task_vector[j] = NULL;
  393. }
  394. }
  395. laser_task_vector.clear();
  396. break;
  397. //退出while(1)
  398. }
  399. //else 直接通过, 然后重新进入 while (1)
  400. usleep(1000 * 100);
  401. }
  402. //暂时不做错误处理,
  403. // 如果有个别雷达扫描故障, 取消雷达子任务之后, 忽略错误
  404. //用其他正常的雷达扫描点云, 继续后面的流程,
  405. // 交给locate去定位识别, 如果识别不出来, 由locate来报错.
  406. if ( t_result != SUCCESS )
  407. {
  408. LOG(INFO) << " laser_task error :::: "<< t_result.to_string()<< this;
  409. // return t_result;
  410. }
  411. //检查雷达任务完成情况,是否是正常完成
  412. LOG(INFO) << " laser scanning over cloud size:" << scan_cloud.size();
  413. //第二步,根据区域筛选点云
  414. pcl::PointCloud<pcl::PointXYZ>::Ptr locate_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  415. pcl::PassThrough<pcl::PointXYZ> passX;
  416. pcl::PassThrough<pcl::PointXYZ> passY;
  417. pcl::PassThrough<pcl::PointXYZ> passZ;
  418. passX.setInputCloud(scan_cloud.makeShared());
  419. passX.setFilterFieldName("x");
  420. passX.setFilterLimits(m_terminor_parameter.area_3d().min_x(), m_terminor_parameter.area_3d().max_x());
  421. passX.filter(*locate_cloud);
  422. passY.setInputCloud(locate_cloud);
  423. passY.setFilterFieldName("y");
  424. passY.setFilterLimits(m_terminor_parameter.area_3d().min_y(), m_terminor_parameter.area_3d().max_y());
  425. passY.filter(*locate_cloud);
  426. passY.setInputCloud(locate_cloud);
  427. passY.setFilterFieldName("z");
  428. passY.setFilterLimits(m_terminor_parameter.area_3d().min_z(), m_terminor_parameter.area_3d().max_z());
  429. passY.filter(*locate_cloud);
  430. LOG(INFO) << "筛选点云点数 : " << locate_cloud->size();
  431. //第三步,创建测量任务, 进入测量中
  432. Locate_task *locate_task = new Locate_task();
  433. locate_task->set_locate_cloud(locate_cloud);
  434. locate_task->set_save_path(project_path);
  435. m_terminor_statu = TERMINOR_MEASURING;
  436. code = mp_locater->execute_task(locate_task);
  437. m_measure_information.locate_correct = false;
  438. //获取测量结果
  439. Locate_information dj_locate_information = locate_task->get_locate_information();
  440. //释放locate task
  441. if (locate_task != NULL) {
  442. delete locate_task;
  443. locate_task = NULL;
  444. }
  445. if (code != SUCCESS) {
  446. return code;
  447. }
  448. //进入万集雷达流程--------
  449. Wj_lidar_Task *wj_task = new Wj_lidar_Task();
  450. code = wj_task->init();
  451. if (code != SUCCESS) {
  452. delete wj_task;
  453. return code;
  454. }
  455. wj_command t_wj_command;
  456. t_wj_command.terminal_id = m_terminor_parameter.id();
  457. t_wj_command.command_time = std::chrono::steady_clock::now();
  458. t_wj_command.timeout_in_milliseconds = 2000;
  459. wj_task->set_command(t_wj_command);
  460. code = mp_wj_lidar->execute_task(wj_task);
  461. if (code != SUCCESS) {
  462. delete wj_task;
  463. return code;
  464. }
  465. ///万集测量正确,对比两数据
  466. wj_measure_result wj_result;
  467. code = wj_task->get_result(wj_result);
  468. if (code != SUCCESS) {
  469. delete wj_task;
  470. return code;
  471. }
  472. Locate_information wj_locate_information;
  473. wj_locate_information.locate_x = wj_result.x;
  474. wj_locate_information.locate_y = wj_result.y;
  475. wj_locate_information.locate_theta = wj_result.angle;
  476. wj_locate_information.locate_wheel_base = wj_result.wheel_base;
  477. wj_locate_information.locate_width = wj_result.width;
  478. //对比两个数据
  479. float offset_x = fabs(dj_locate_information.locate_x - wj_locate_information.locate_x);
  480. float offset_y = fabs(dj_locate_information.locate_y - wj_locate_information.locate_y);
  481. float offset_angle = fabs(dj_locate_information.locate_theta - wj_locate_information.locate_theta);
  482. float offset_width = fabs(dj_locate_information.locate_width - wj_locate_information.locate_width);
  483. float offset_wheel_base = fabs(
  484. dj_locate_information.locate_wheel_base - wj_locate_information.locate_wheel_base);
  485. if (offset_x > 100 || offset_y > 150 || offset_angle > 5 || offset_wheel_base > 550 || offset_width > 250) {
  486. LOG(WARNING) << "chekc failed. (offset x>100, y>150, angle>5, wheel_base>550, width>250): " << offset_x
  487. << " " << offset_y << " " << offset_angle << " " << offset_wheel_base << " " << offset_width;
  488. return Error_manager(TERMINOR_CHECK_RESULTS_ERROR, NORMAL, "check results failed ");
  489. }
  490. ///根据sigmod函数计算角度权重
  491. double angle_weight=1.0-1.0/(1.0+exp(-offset_angle/1.8));
  492. ///根据两个结果选择最优结果,中心点选择万集雷达,角度选择两值加权,轴距已以2750为基准作卡尔曼滤波
  493. ///车长以大疆雷达为准,车宽以万集雷达为准,高以大疆雷达为准
  494. m_measure_information.locate_x = wj_locate_information.locate_x;
  495. m_measure_information.locate_y = wj_locate_information.locate_y;
  496. m_measure_information.locate_theta =angle_weight * wj_locate_information.locate_theta +
  497. (1.0-angle_weight) * dj_locate_information.locate_theta;
  498. float dj_distance = fabs(dj_locate_information.locate_wheel_base - 2750);
  499. float wj_distance = fabs(wj_locate_information.locate_wheel_base - 2750);
  500. float weight_dj = wj_distance / (dj_distance + wj_distance);
  501. float weight_wj = dj_distance / (dj_distance + wj_distance);
  502. m_measure_information.locate_wheel_base = weight_dj * dj_locate_information.locate_wheel_base +
  503. weight_wj * wj_locate_information.locate_wheel_base;
  504. m_measure_information.locate_length = dj_locate_information.locate_length;
  505. m_measure_information.locate_width = wj_locate_information.locate_width;
  506. m_measure_information.locate_hight = dj_locate_information.locate_hight;
  507. m_measure_information.locate_correct = true;
  508. ////如果测量正确,检验结果
  509. if (mp_verify_tool != NULL) {
  510. cv::RotatedRect rotated_rect;
  511. rotated_rect.center = cv::Point2f(m_measure_information.locate_x, m_measure_information.locate_y);
  512. rotated_rect.angle = m_measure_information.locate_theta;
  513. float ext_length = 720;
  514. float robot_width = 2650.0;
  515. float new_length = m_measure_information.locate_length + ext_length * 2.0;
  516. rotated_rect = create_rotate_rect(new_length, robot_width, m_measure_information.locate_theta,
  517. m_measure_information.locate_x, m_measure_information.locate_y);
  518. code = mp_verify_tool->verify(rotated_rect, m_measure_information.locate_hight, false);
  519. m_measure_information.locate_correct = (code == SUCCESS);
  520. delete wj_task;
  521. return code;
  522. } else {
  523. delete wj_task;
  524. }
  525. return code;
  526. }
  527. cv::RotatedRect Terminor_Command_Executor::create_rotate_rect(float length,float width,float angle,float cx,float cy)
  528. {
  529. const double C_PI=3.14159265;
  530. float theta=C_PI*(angle/180.0);
  531. float a00=cos(theta);
  532. float a01=-sin(theta);
  533. float a10=sin(theta);
  534. float a11=cos(theta);
  535. cv::Point2f point[4];
  536. point[0].x=-length/2.0;
  537. point[0].y=-width/2.0;
  538. point[1].x=-length/2.0;
  539. point[1].y=width/2.0;
  540. point[2].x=length/2.0;
  541. point[2].y=-width/2.0;
  542. point[3].x=length/2.0;
  543. point[3].y=width/2.0;
  544. std::vector<cv::Point2f> point_vec;
  545. for(int i=0;i<4;++i)
  546. {
  547. float x=point[i].x*a00+point[i].y*a01+cx;
  548. float y=point[i].x*a10+point[i].y*a11+cy;
  549. point_vec.push_back(cv::Point2f(x,y));
  550. }
  551. return cv::minAreaRect(point_vec);
  552. }