navigation.cpp 34 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135
  1. //
  2. // Created by zx on 22-12-2.
  3. //
  4. #include "navigation.h"
  5. #include "loaded_mpc.h"
  6. #include "../define/TimerRecord.h"
  7. Navigation::~Navigation()
  8. {
  9. exit_=true;
  10. if(terminator_)
  11. delete terminator_;
  12. if(brotherEmqx_)
  13. delete brotherEmqx_;
  14. if(monitor_)
  15. delete monitor_;
  16. if(thread_!= nullptr)
  17. {
  18. if(thread_->joinable())
  19. thread_->join();
  20. delete thread_;
  21. }
  22. if(pubthread_!= nullptr)
  23. {
  24. if(pubthread_->joinable())
  25. pubthread_->join();
  26. delete pubthread_;
  27. }
  28. }
  29. /*
  30. * 高斯函数压缩,x=3
  31. */
  32. double limit_gause(double x,double min,double max){
  33. double r=x>=0?1.0:-1.0;
  34. double delta=max/1.0;
  35. return (max-(max-min)*exp(-x*x/(delta*delta)))*r;
  36. }
  37. double limit(double x,double min,double max){
  38. double ret=x;
  39. if(x>=0){
  40. if(x>max) ret=max;
  41. if(x<min) ret=min;
  42. }else{
  43. if(x<-max) ret=-max;
  44. if(x>-min) ret=-min;
  45. }
  46. return ret;
  47. }
  48. double next_speed(double speed,double target_speed,double acc,double dt)
  49. {
  50. if(fabs(target_speed-speed)/dt<acc)
  51. {
  52. return target_speed;
  53. }
  54. else
  55. {
  56. double r=target_speed-speed>=0.?1.0:-1.0;
  57. return speed+r*acc*dt;
  58. }
  59. }
  60. bool Navigation::PoseTimeout(){
  61. if(timedPose_.timeout()== false && timedBrotherPose_.timeout()==false){
  62. return false;
  63. }else{
  64. if(timedPose_.timeout()){
  65. printf(" current pose is timeout \n");
  66. }
  67. if(timedBrotherPose_.timeout()){
  68. printf(" brother pose is timeout \n");
  69. }
  70. return true;
  71. }
  72. }
  73. bool Navigation::Init(const NavParameter::Navigation_parameter& parameter)
  74. {
  75. parameter_=parameter;
  76. NavParameter::AgvEmqx_parameter agv_p=parameter.agv_emqx();
  77. if(monitor_== nullptr) {
  78. monitor_ = new Monitor_emqx(agv_p.nodeid());
  79. if(monitor_->Connect(agv_p.ip(),agv_p.port())==false)
  80. {
  81. printf(" agv emqx connected failed\n");
  82. return false;
  83. }
  84. monitor_->set_speedcmd_topic(agv_p.pubspeedtopic());
  85. monitor_->AddCallback(agv_p.subposetopic(),Navigation::RobotPoseCallback,this);
  86. monitor_->AddCallback(agv_p.subspeedtopic(),Navigation::RobotSpeedCallback,this);
  87. }
  88. NavParameter::Emqx_parameter terminal_p=parameter.terminal_emqx();
  89. if(terminator_== nullptr) {
  90. terminator_ = new Terminator_emqx(terminal_p.nodeid());
  91. if(terminator_->Connect(terminal_p.ip(),terminal_p.port())==false)
  92. {
  93. printf(" terminator emqx connected failed\n");
  94. return false;
  95. }
  96. terminator_->AddCallback(terminal_p.subnavcmdtopic(),Navigation::NavCmdCallback,this);
  97. }
  98. if(parameter.has_brother_emqx()) {
  99. NavParameter::BrotherEmqx brotherEmqx = parameter.brother_emqx();
  100. if (brotherEmqx_ == nullptr) {
  101. brotherEmqx_ = new Terminator_emqx(brotherEmqx.nodeid());
  102. if (brotherEmqx_->Connect(brotherEmqx.ip(), brotherEmqx.port()) == true) {
  103. brotherEmqx_->AddCallback(brotherEmqx.subbrotherstatutopic(), Navigation::BrotherAgvStatuCallback, this);
  104. }else{
  105. printf(" brother emqx connected failed\n");
  106. // return false;
  107. }
  108. }
  109. }
  110. inited_=true;
  111. if(pubthread_!= nullptr)
  112. {
  113. exit_=true;
  114. if(pubthread_->joinable())
  115. pubthread_->join();
  116. delete pubthread_;
  117. }
  118. exit_=false;
  119. pubthread_=new std::thread(&Navigation::pubStatuThreadFuc,this);
  120. return true;
  121. }
  122. void Navigation::RobotPoseCallback(const MqttMsg& msg,void* context)
  123. {
  124. Navigation* navigator=(Navigation*)context;
  125. NavMessage::LidarOdomStatu statu;
  126. if(msg.toProtoMessage(statu))
  127. {
  128. navigator->ResetPose(Pose2d(statu.x(),statu.y(),statu.theta()));
  129. }
  130. }
  131. void Navigation::HandleAgvStatu(const MqttMsg& msg)
  132. {
  133. NavMessage::AgvStatu speed;
  134. if(msg.toProtoMessage(speed))
  135. {
  136. ResetStatu(speed.v(),speed.w());
  137. ResetClamp((ClampStatu)speed.clamp());
  138. }
  139. }
  140. void Navigation::RobotSpeedCallback(const MqttMsg& msg,void* context)
  141. {
  142. Navigation* navigator=(Navigation*)context;
  143. navigator->HandleAgvStatu(msg);
  144. }
  145. void Navigation::pubStatuThreadFuc(void* p) {
  146. Navigation *navogator = (Navigation *) p;
  147. if (navogator) {
  148. while (navogator->exit_ == false) {
  149. std::this_thread::sleep_for(std::chrono::milliseconds(50));
  150. NavMessage::NavStatu statu;
  151. statu.set_main_agv(false);
  152. navogator->publish_statu(statu);
  153. }
  154. }
  155. }
  156. void Navigation::publish_statu(NavMessage::NavStatu& statu) {
  157. if(timedPose_.timeout()==false){
  158. NavMessage::LidarOdomStatu odom;
  159. odom.set_x(timedPose_.Get().x());
  160. odom.set_y(timedPose_.Get().y());
  161. odom.set_theta(timedPose_.Get().theta());
  162. if(timedV_.timeout()==false)
  163. odom.set_v(timedV_.Get());
  164. if(timedA_.timeout()==false)
  165. odom.set_vth(timedA_.Get());
  166. statu.mutable_odom()->CopyFrom(odom);
  167. }
  168. statu.set_in_space(isInSpace_);
  169. if(isInSpace_) statu.set_space_id(space_id_);
  170. //发布nav状态
  171. statu.set_statu(actionType_); //
  172. statu.set_move_mode(move_mode_);
  173. if (running_)
  174. {
  175. statu.set_key(global_navCmd_.key());
  176. }
  177. //发布MPC信息
  178. //发布mpc 预选点
  179. if (selected_traj_.timeout() == false) {
  180. for (int i = 0; i < selected_traj_.Get().size(); ++i) {
  181. Pose2d pt = selected_traj_.Get()[i];
  182. NavMessage::Pose2d *pose = statu.mutable_selected_traj()->add_poses();
  183. pose->set_x(pt.x());
  184. pose->set_y(pt.y());
  185. pose->set_theta(pt.theta());
  186. }
  187. }
  188. //发布 mpc 预测点
  189. if (predict_traj_.timeout() == false) {
  190. for (int i = 0; i < predict_traj_.Get().size(); ++i) {
  191. Pose2d pt = predict_traj_.Get()[i];
  192. NavMessage::Pose2d *pose = statu.mutable_predict_traj()->add_poses();
  193. pose->set_x(pt.x());
  194. pose->set_y(pt.y());
  195. pose->set_theta(pt.theta());
  196. }
  197. }
  198. //std::cout<<"nav statu:"<<statu.DebugString()<<std::endl;
  199. MqttMsg msg;
  200. msg.fromProtoMessage(statu);
  201. if(terminator_)
  202. terminator_->Publish(parameter_.terminal_emqx().pubnavstatutopic(),msg);
  203. //发布位姿 ------robot状态--------------------------
  204. NavMessage::RobotStatu robot;
  205. if(CreateRobotStatuMsg(robot)) {
  206. if (terminator_) {
  207. MqttMsg msg;
  208. msg.fromProtoMessage(robot);
  209. terminator_->Publish(parameter_.terminal_emqx().pubstatutopic(), msg);
  210. }
  211. }
  212. }
  213. bool Navigation::CreateRobotStatuMsg(NavMessage::RobotStatu& robotStatu)
  214. {
  215. //printf(" %d %d %d \n",timedPose_.timeout(),timedV_.timeout(),timedA_.timeout());
  216. if (timedPose_.timeout() == false) {
  217. Pose2d pose = timedPose_.Get();
  218. robotStatu.set_x(pose.x());
  219. robotStatu.set_y(pose.y());
  220. robotStatu.set_theta(pose.theta());
  221. if((timedV_.timeout() == false && timedA_.timeout() == false)) {
  222. NavMessage::AgvStatu plc;
  223. plc.set_v(timedV_.Get());
  224. plc.set_w(timedA_.Get());
  225. plc.set_clamp(timed_clamp_.Get());
  226. //printf(" timed_clamp_:%d\n ",timed_clamp_.Get());
  227. robotStatu.mutable_agvstatu()->CopyFrom(plc);
  228. }
  229. return true;
  230. }
  231. return false;
  232. }
  233. void Navigation::ResetStatu(double v,double a)
  234. {
  235. timedV_.reset(v,0.5);
  236. timedA_.reset(a,0.5);
  237. }
  238. void Navigation::ResetClamp(ClampStatu statu){
  239. timed_clamp_.reset(statu,1);
  240. }
  241. void Navigation::ResetPose(const Pose2d& pose)
  242. {
  243. timedPose_.reset(pose,1.0);
  244. }
  245. bool Navigation::Start(const NavMessage::NavCmd& cmd)
  246. {
  247. if(newUnfinished_cations_.empty()==false) //正在运行中,上一次指令未完成
  248. {
  249. if(pause_)
  250. {
  251. pause_=false;
  252. return true;
  253. }
  254. printf(" navigation is running pls cancel before\n");
  255. return false;
  256. }
  257. if(thread_!= nullptr)
  258. {
  259. if(thread_->joinable())
  260. thread_->join();
  261. delete thread_;
  262. }
  263. //add 先检查当前点与起点的距离
  264. global_navCmd_=cmd;
  265. for (int i = 0; i < cmd.newactions_size(); ++i)
  266. newUnfinished_cations_.push(cmd.newactions(i));
  267. thread_=new std::thread(&Navigation::navigatting,this);
  268. return true;
  269. }
  270. void Navigation::Cancel()
  271. {
  272. cancel_=true;
  273. }
  274. bool Navigation::Stop() {
  275. if(monitor_)
  276. {
  277. monitor_->stop();
  278. while(cancel_==false)
  279. {
  280. if(timedV_.timeout()==false && timedA_.timeout()==false)
  281. {
  282. if(fabs(timedV_.Get())<1e-2 && fabs(timedA_.Get())<1e-3)
  283. return true;
  284. else
  285. monitor_->stop();
  286. printf("Stoped wait V/A ==0(1e-4,1e-4),V:%f,A:%f\n",fabs(timedV_.Get()),fabs(timedA_.Get()));
  287. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  288. }else{
  289. printf("Stop failed V/A timeout\n");
  290. return false;
  291. }
  292. }
  293. }
  294. printf("stoped ret false.\n");
  295. return false;
  296. }
  297. bool Navigation::SlowlyStop() {
  298. double acc = 3.0;
  299. double dt = 0.1;
  300. while (cancel_ == false) {
  301. if (timedV_.timeout() == false) {
  302. double v = timedV_.Get();
  303. if(fabs(v<1e-2 && fabs(timedA_.Get())<1e-3))
  304. return true;
  305. if (v > 0) {
  306. double new_v = v - acc * dt;
  307. new_v = new_v > 0 ? new_v : 0;
  308. SendMoveCmd(move_mode_, Monitor_emqx::ActionType(actionType_), new_v,0);
  309. }else{
  310. double new_v = v + acc * dt;
  311. new_v = new_v < 0 ? new_v : 0;
  312. SendMoveCmd(move_mode_, Monitor_emqx::ActionType(actionType_), new_v,0);
  313. }
  314. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  315. } else {
  316. printf("Stop failed V/A timeout\n");
  317. return false;
  318. }
  319. }
  320. printf("stoped ret false.\n");
  321. return false;
  322. }
  323. void Navigation::Pause()
  324. {
  325. if(Stop())
  326. pause_=true;
  327. }
  328. Navigation::Navigation()
  329. {
  330. isInSpace_=false; //是否在车位或者正在进入车位
  331. RWheel_position_=eUnknow;
  332. move_mode_=Monitor_emqx::eSingle;
  333. thread_= nullptr;
  334. monitor_= nullptr;
  335. terminator_= nullptr;
  336. timedBrotherPose_.reset(Pose2d(-100,0,0),0.5);
  337. }
  338. void Navigation::BrotherAgvStatuCallback(const MqttMsg& msg,void* context)
  339. {
  340. Navigation* navigator=(Navigation*)context;
  341. NavMessage::NavStatu brother_statu;
  342. if(msg.toProtoMessage(brother_statu)==false) {
  343. std::cout<<" msg transform to AGVStatu failed,msg:"<<msg.data()<<std::endl;
  344. return;
  345. }
  346. //std::cout<<brother_nav.DebugString()<<std::endl<<std::endl;
  347. if(brother_statu.has_odom()) {
  348. NavMessage::LidarOdomStatu odom = brother_statu.odom();
  349. Pose2d pose(odom.x(), odom.y(), odom.theta());
  350. navigator->timedBrotherPose_.reset(pose, 1);
  351. navigator->timedBrotherV_.reset(odom.v(), 1);
  352. navigator->timedBrotherA_.reset(odom.vth(), 1);
  353. navigator->timedBrotherNavStatu_.reset(brother_statu,0.1);
  354. }
  355. }
  356. void Navigation::HandleNavCmd(const NavMessage::NavCmd& cmd)
  357. {
  358. if(cmd.action()==3)
  359. {
  360. printf(" Nav cancel\n");
  361. Cancel();
  362. return ;
  363. }
  364. if(cmd.action()==2) {
  365. printf(" Nav continue\n");
  366. pause_=false;
  367. return ;
  368. }
  369. if(cmd.action()==1) {
  370. printf(" Nav pause\n");
  371. Pause();
  372. return ;
  373. }
  374. if(cmd.action()==0||cmd.action()==6)
  375. {
  376. Start(cmd);
  377. }
  378. else
  379. printf(" Invalid action ,action:%d\n",cmd.action());
  380. }
  381. void Navigation::NavCmdCallback(const MqttMsg& msg,void* context)
  382. {
  383. NavMessage::NavCmd cmd;
  384. if(msg.toProtoMessage(cmd)==false) {
  385. printf(" msg transform to NavCmd failed ..!!\n");
  386. return;
  387. }
  388. Navigation* navigator=(Navigation*)context;
  389. navigator->HandleNavCmd(cmd);
  390. }
  391. bool Navigation::RotateReferToTarget(const Pose2d& target,stLimit limit_rotate,bool anyDirect) {
  392. while(cancel_==false) {
  393. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  394. if (timedPose_.timeout()) {
  395. printf(" RotateBytarget failed pose timeout\n");
  396. return false;
  397. }
  398. if (timedA_.timeout()) {
  399. printf(" RotateBytarget failed wmg timeout\n");
  400. return false;
  401. }
  402. Pose2d targetInPose = Pose2d::relativePose(target, timedPose_.Get());
  403. float yawDiff = Pose2d::vector2yaw(targetInPose.x(), targetInPose.y());
  404. float minYawdiff = yawDiff;
  405. if (anyDirect) {
  406. Pose2d p0 = timedPose_.Get();
  407. float yawdiff[4] = {0};
  408. yawdiff[0] = yawDiff;
  409. Pose2d relativePose;
  410. relativePose = Pose2d::relativePose(target, p0 - Pose2d(0, 0, M_PI / 2));
  411. yawdiff[1] = Pose2d::vector2yaw(relativePose.x(), relativePose.y()); ////使用减法,保证角度在【-pi pi】
  412. relativePose = Pose2d::relativePose(target, p0 - Pose2d(0, 0, M_PI));
  413. yawdiff[2] = Pose2d::vector2yaw(relativePose.x(), relativePose.y());
  414. relativePose = Pose2d::relativePose(target, p0 - Pose2d(0, 0, 3 * M_PI / 2));
  415. yawdiff[3] = Pose2d::vector2yaw(relativePose.x(), relativePose.y());
  416. for (int i = 1; i < 4; ++i) {
  417. if (fabs(yawdiff[i]) < fabs(minYawdiff)) {
  418. minYawdiff = yawdiff[i];
  419. targetInPose=Pose2d::relativePose(target,p0-Pose2d(0,0,i*M_PI/2.0));
  420. }
  421. }
  422. }
  423. /*std::cout<<" Rotate refer to target:"<<target<<",targetInPose:"
  424. <<targetInPose<<",anyDirect:"<<anyDirect<<std::endl;*/
  425. //以当前点为原点,想方向经过目标点的二次曲线曲率>0.25,则需要调整 y=a x*x
  426. float cuv=compute_cuv(targetInPose);
  427. float dt=0.1;
  428. float acc_angular=15*M_PI/180.0;
  429. if (cuv>2*M_PI/180.0) {
  430. double theta = limit_gause(minYawdiff, limit_rotate.min, limit_rotate.max);
  431. double angular = next_speed(timedA_.Get(), theta, acc_angular, dt);
  432. double limit_angular = limit(angular, limit_rotate.min, limit_rotate.max);
  433. SendMoveCmd(move_mode_, Monitor_emqx::eRotate, 0, limit_angular);
  434. actionType_ = eRotation;
  435. printf(" Ratate | input anguar:%f,next angular:%f,down:%f diff:%f anyDitect:%d\n",
  436. timedA_.Get(), angular, limit_angular, minYawdiff, anyDirect);
  437. continue;
  438. }else{
  439. if(fabs(timedA_.Get())<5*M_PI/180.0) {
  440. printf(" Rotate refer target completed,cuv:%f\n", cuv);
  441. return true;
  442. }
  443. continue;
  444. }
  445. }
  446. return false;
  447. }
  448. bool Navigation::MoveToTarget(NavMessage::PathNode node, Navigation::stLimit limit_v, Navigation::stLimit limit_w,
  449. bool anyDirect,bool enable_rotate) {
  450. if (IsArrived(node)) {
  451. return true;
  452. }
  453. bool already_in_mpc=false;
  454. while (cancel_ == false) {
  455. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  456. if (PoseTimeout()) {
  457. printf(" navigation Error:Pose is timeout \n");
  458. break;
  459. }
  460. Pose2d current=timedPose_.Get();
  461. if (IsArrived(node)) {
  462. break;
  463. }
  464. //两个方向都无法到达目标点,旋转 朝向目标点
  465. bool x_enable=PossibleToTarget(node,false);
  466. bool y_enable=PossibleToTarget(node,true);
  467. bool enableTotarget=x_enable||y_enable;
  468. if(anyDirect==false){
  469. enableTotarget=x_enable;
  470. }
  471. //巡线无法到达目标点
  472. if(enableTotarget==false) {
  473. if(already_in_mpc && enable_rotate==false) {
  474. printf(" Move to node failed ,impossible to target and rotate is not enabled\n");
  475. return false;
  476. }
  477. Pose2d target(node.x(), node.y(), 0);
  478. if (RotateReferToTarget(target, limit_w, anyDirect) == false) {
  479. std::cout << " Rotate refer to target failed,target:" << target <<
  480. " anyDirect:" << anyDirect << std::endl;
  481. return false;
  482. }
  483. continue;
  484. }
  485. already_in_mpc=true;
  486. MpcResult ret = MpcToTarget(node, limit_v, anyDirect);
  487. if (ret == eMpcSuccess) {
  488. printf(" MPC to target:%f %f l:%f,w:%f theta:%f completed\n",
  489. node.x(),node.y(),node.l(),node.w(),node.theta());
  490. break;
  491. } else if (ret == eImpossibleToTarget) {
  492. printf(" MPC to target:%f %f l:%f,w:%f theta:%f impossible ,retry ..............................\n",
  493. node.x(),node.y(),node.l(),node.w(),node.theta());
  494. } else {
  495. return false;
  496. }
  497. }
  498. if (cancel_) {
  499. return false;
  500. }
  501. return true;
  502. }
  503. bool Navigation::execute_nodes(NavMessage::NewAction action)
  504. {
  505. if(action.type()==3 || action.type()==4) //最优动作导航 or 导航中保证朝向严格一致
  506. {
  507. if(!parameter_.has_nodeangularlimit()|| !parameter_.has_nodevelocitylimit()||action.pathnodes_size()==0) {
  508. std::cout << "execute pathNodes failed ,Action invalid:" << action.DebugString() << std::endl;
  509. return false;
  510. }
  511. bool anyDirect=(action.type()==3);
  512. //速度限制
  513. stLimit adjust_angular={ parameter_.nodeangularlimit().min(),parameter_.nodeangularlimit().max() };
  514. stLimit mpc_velocity={ parameter_.nodevelocitylimit().min(),parameter_.nodevelocitylimit().max() };
  515. for(int i=0;i< action.pathnodes_size();++i) {
  516. NavMessage::PathNode node = action.pathnodes(i);
  517. if(i+1<action.pathnodes_size()){
  518. NavMessage::PathNode next = action.pathnodes(i+1);
  519. Pose2d vec(next.x()-node.x(),next.y()-node.y(),0);
  520. node.set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
  521. node.set_l(0.3);
  522. node.set_w(0.1);
  523. }else{
  524. node.set_theta(0);
  525. node.set_w(0.2);
  526. node.set_l(0.2);
  527. }
  528. if(MoveToTarget(node,mpc_velocity,adjust_angular,anyDirect,true)==false)
  529. return false;
  530. else
  531. isInSpace_=false;
  532. }
  533. return true;
  534. }
  535. printf("execute PathNode failed ,action type is not 3/4 :%d\n",action.type());
  536. return false;
  537. }
  538. bool Navigation::RotateBeforeEnterSpace(NavMessage::PathNode space,double wheelbase,NavMessage::PathNode& target) {
  539. if (timedBrotherNavStatu_.timeout() || timedPose_.timeout()) {
  540. printf(" rotate failed : timedBrotherNavStatu_ or pose timeout\n");
  541. return false;
  542. }
  543. NavMessage::NavStatu brother = timedBrotherNavStatu_.Get();
  544. stLimit limit_rotate = {2 * M_PI / 180.0, 15 * M_PI / 180.0};
  545. double acc_angular = 20 * M_PI / 180.0;
  546. double dt = 0.1;
  547. Pose2d rotated = timedPose_.Get();
  548. //前车先到,当前车进入2点,保持与前车一致的朝向
  549. if (brother.in_space() && brother.space_id() == space.id()) {
  550. rotated.mutable_theta() = brother.odom().theta();
  551. } else { //当前车先到(后车),倒车入库
  552. rotated.mutable_theta() = space.theta();
  553. rotated = rotated.rotate(rotated.x(), rotated.y(), M_PI);
  554. }
  555. double x = space.x() - wheelbase/2 * cos(rotated.theta());
  556. double y = space.y() - wheelbase/2 * sin(rotated.theta());
  557. target.set_x(x);
  558. target.set_y(y);
  559. target.set_theta(rotated.theta());
  560. target.set_l(0.05);
  561. target.set_w(0.03);
  562. target.set_id(space.id());
  563. //整车协调的时候,保持前后与车位一致即可
  564. if(move_mode_==Monitor_emqx::eMain){
  565. double yawDiff1 = (rotated - timedPose_.Get()).theta();
  566. double yawDiff2 = (rotated+Pose2d(0,0,M_PI) - timedPose_.Get()).theta();
  567. if(fabs(yawDiff1)<fabs(yawDiff2)){
  568. rotated=rotated+Pose2d(0,0,M_PI);
  569. }
  570. }
  571. while (cancel_ == false) {
  572. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  573. Pose2d current = timedPose_.Get();
  574. double yawDiff = (rotated - current).theta();
  575. if (fabs(yawDiff) > 1 * M_PI / 180.0) {
  576. double theta = limit_gause(yawDiff, limit_rotate.min, limit_rotate.max);
  577. double angular = next_speed(timedA_.Get(), theta, acc_angular, dt);
  578. double limit_angular = limit(angular, limit_rotate.min, limit_rotate.max);
  579. SendMoveCmd(move_mode_, Monitor_emqx::eRotate, 0, limit_angular);
  580. actionType_ = eRotation;
  581. printf(" RotateBeforeEnterSpace | input anguar:%f,next angular:%f,down:%f diff:%f anyDirect:false\n",
  582. timedA_.Get(), angular, limit_angular, yawDiff);
  583. continue;
  584. } else {
  585. if (fabs(timedA_.Get()) < 5 * M_PI / 180.0) {
  586. printf(" RotateBeforeEnterSpace refer target completed\n");
  587. printf("---------------- update new target :%f %f %f \n",target.x(),target.y(),target.theta());
  588. return true;
  589. }
  590. }
  591. }
  592. return false;
  593. }
  594. bool Navigation::execute_InOut_space(NavMessage::NewAction action) {
  595. if (action.type() != 1 && action.type() != 2) {
  596. printf(" Inout_space failed : msg action type must ==1\n ");
  597. return false;
  598. }
  599. if (!parameter_.has_inoutvlimit() || !action.has_spacenode() ||
  600. !action.has_streetnode()) {
  601. std::cout << "execute enter_space failed ,Action miss some infos:" << action.DebugString() << std::endl;
  602. return false;
  603. }
  604. if (PoseTimeout() == true) {
  605. printf(" inout_space failed type:%d : current pose is timeout\n", action.type());
  606. return false;
  607. }
  608. stLimit limit_v={parameter_.inoutvlimit().min(),parameter_.inoutvlimit().max()};
  609. stLimit limit_w={2*M_PI/180.0,20*M_PI/180.0};
  610. //入库,起点为streetNode
  611. if(action.type()==1){
  612. Pose2d vec(action.spacenode().x()-action.streetnode().x(),action.spacenode().y()-action.streetnode().y(),0);
  613. action.mutable_streetnode()->set_l(0.2);
  614. action.mutable_streetnode()->set_w(0.05);
  615. action.mutable_streetnode()->set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
  616. if(MoveToTarget(action.streetnode(),limit_v,limit_w,true,true)==false)
  617. {
  618. printf(" Enter space failed type:%d: MoveTo StreetNode failed\n", action.type());
  619. return false;
  620. }
  621. //移动到库位点, 禁止任意方向// 不允许巡线中停下旋转(当无法到达目标点时,返回false)
  622. printf("inout ----------------------------------------\n");
  623. //计算车位朝向
  624. action.mutable_spacenode()->set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
  625. //计算当前车是进入车位1点还是2点
  626. NavMessage::PathNode new_atrget;
  627. if(RotateBeforeEnterSpace(action.spacenode(),action.wheelbase(),new_atrget)==false){
  628. return false;
  629. }
  630. if(MoveToTarget(new_atrget,limit_v,limit_w,true,false)==false)
  631. {
  632. printf(" Enter space failed type:%d: MoveTo StreetNode failed\n", action.type());
  633. return false;
  634. }
  635. }else if(action.type()==2){
  636. Pose2d space(action.spacenode().x(),action.spacenode().y(),0);
  637. Pose2d diff=Pose2d::abs(Pose2d::relativePose(space,timedPose_.Get()));
  638. if(diff.y()<0.05){
  639. //出库,移动到马路点,允许自由方向,不允许中途旋转
  640. Pose2d vec(action.streetnode().x()-action.spacenode().x(),action.streetnode().y()-action.spacenode().y(),0);
  641. action.mutable_streetnode()->set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
  642. action.mutable_streetnode()->set_l(0.2);
  643. action.mutable_streetnode()->set_w(0.1);
  644. if(MoveToTarget(action.streetnode(),limit_v,limit_w,true,false)==false){
  645. printf(" out space failed type:%d: MoveTo StreetNode failed\n", action.type());
  646. return false;
  647. }
  648. }else{
  649. std::cout<<" Out space failed: current pose too far from space node:"<<space<<",diff:"<<diff<<std::endl;
  650. return false;
  651. }
  652. }
  653. return true;
  654. }
  655. bool Navigation::mpc_once(Trajectory traj,stLimit limit_v,std::vector<double>& out,bool directY) {
  656. if (PoseTimeout() == true) {
  657. printf(" MPC once Error:Pose is timeout \n");
  658. return false;
  659. }
  660. if(timedV_.timeout() == true || timedA_.timeout() == true){
  661. printf(" MPC once Error:V/A is timeout \n");
  662. return false;
  663. }
  664. if (traj.size() == 0) {
  665. printf("traj size ==0\n");
  666. return false;
  667. }
  668. Pose2d pose = timedPose_.Get();
  669. double velocity = timedV_.Get(); //从plc获取状态
  670. double angular = timedA_.Get();
  671. Eigen::VectorXd statu = Eigen::VectorXd::Zero(5);//agv状态
  672. statu[0] = pose.x();
  673. statu[1] = pose.y();
  674. statu[2] = pose.theta();
  675. statu[3] = velocity;
  676. statu[4] = angular;
  677. Trajectory optimize_trajectory;
  678. Trajectory selected_trajectory;
  679. NavParameter::MPC_parameter mpc_parameter=parameter_.x_mpc_parameter();
  680. double obs_w=0.85;
  681. double obs_h=1.45;
  682. if (directY == true) {
  683. //将车身朝向旋转90°,车身朝向在(-pi,pi]
  684. statu[2] += M_PI / 2;
  685. if (statu[2] > M_PI)
  686. statu[2] -= 2 * M_PI;
  687. mpc_parameter=parameter_.y_mpc_parameter();
  688. obs_w=1.45;
  689. obs_h=0.85;
  690. }
  691. Pose2d brother = timedBrotherPose_.Get();
  692. Pose2d relative = Pose2d::relativePose(brother, pose);
  693. if(directY)
  694. relative = Pose2d::relativePose(brother.rotate(brother.x(),brother.y(),M_PI/2), pose.rotate(pose.x(),pose.y(),M_PI/2));//计算另一节在当前小车坐标系下的坐标
  695. //std::cout<<"pose:"<<pose<<", brother:"<<brother<<", relative:"<<relative<<std::endl;
  696. if (move_mode_ == Monitor_emqx::ActionMode::eMain)
  697. relative = Pose2d(-1e8, -1e8, 0);
  698. MpcError ret = failed;
  699. LoadedMPC MPC(relative, obs_w,obs_h,limit_v.min, limit_v.max);
  700. LoadedMPC::MPC_parameter parameter={mpc_parameter.shortest_radius(),mpc_parameter.dt(),
  701. mpc_parameter.acc_velocity(),mpc_parameter.acc_angular()};
  702. //printf(" r:%f dt:%f acc:%f acc_a:%f\n",mpc_parameter.shortest_radius(),
  703. // mpc_parameter.dt(),mpc_parameter.acc_velocity(),mpc_parameter.acc_angular());
  704. ret = MPC.solve(traj, traj[traj.size() - 1], statu,parameter,
  705. out, selected_trajectory, optimize_trajectory);
  706. //std::cout<<" traj size %d %d -------- "<<selected_trajectory.size()<<","<<optimize_trajectory.size()<<std::endl;
  707. if(ret==no_solution) {
  708. printf(" mpc solve no solution set v/w = 0\n");
  709. out.clear();
  710. out.push_back(0);
  711. out.push_back(0);
  712. }
  713. predict_traj_.reset(optimize_trajectory, 1);
  714. selected_traj_.reset(selected_trajectory, 1);
  715. return ret==success || ret==no_solution;
  716. }
  717. bool Navigation::IsArrived(NavMessage::PathNode targetNode)
  718. {
  719. if(timedPose_.timeout()|| timedV_.timeout()||timedA_.timeout()){
  720. printf(" pose / v / w timeout,IsArrived return false\n");
  721. return false;
  722. }
  723. Pose2d current=timedPose_.Get();
  724. double x=current.x();
  725. double y=current.y();
  726. double tx=targetNode.x();
  727. double ty=targetNode.y();
  728. double l=fabs(targetNode.l());
  729. double w=fabs(targetNode.w());
  730. double theta=-targetNode.theta();
  731. if(l<1e-10 || w<1e-10){
  732. printf("IsArrived: Error target l or w == 0\n");
  733. return false;
  734. }
  735. double a=(x-tx)*cos(theta)-(y-ty)*sin(theta);
  736. double b=(x-tx)*sin(theta)+(y-ty)*cos(theta);
  737. if( pow(a/l,8)+pow(b/w,8) <=1){
  738. if(fabs(timedV_.Get())<0.06 && fabs(timedA_.Get())<5*M_PI/180.0) {
  739. printf(" Arrived target: %f %f l:%f w:%f theta:%f\n",tx,ty,l,w,theta);
  740. return true;
  741. }
  742. }
  743. return false;
  744. }
  745. void Navigation::SendMoveCmd(Monitor_emqx::ActionMode mode,Monitor_emqx::ActionType type,
  746. double v,double angular){
  747. if(monitor_) {
  748. monitor_->set_speed(mode, type, v, angular);
  749. if(mode==ActionType::eRotation)
  750. RWheel_position_=eR;
  751. if(mode==ActionType::eVertical)
  752. RWheel_position_=eX;
  753. if(mode==ActionType::eHorizon)
  754. RWheel_position_=eY;
  755. }
  756. }
  757. bool Navigation::clamp_close()
  758. {
  759. if(monitor_) {
  760. printf("Clamp closing...\n");
  761. monitor_->clamp_close(move_mode_);
  762. actionType_=eClampClose;
  763. while (cancel_ == false) {
  764. if (timed_clamp_.timeout()) {
  765. printf("timed clamp is timeout\n");
  766. return false;
  767. }
  768. if (timed_clamp_.Get() == eClosed)
  769. return true;
  770. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  771. monitor_->clamp_close(move_mode_);
  772. actionType_=eClampClose;
  773. }
  774. return false;
  775. }
  776. return false;
  777. }
  778. bool Navigation::clamp_open() {
  779. if(monitor_) {
  780. printf("Clamp openning...\n");
  781. monitor_->clamp_open(move_mode_);
  782. actionType_=eClampOpen;
  783. while(cancel_==false)
  784. {
  785. if(timed_clamp_.timeout())
  786. {
  787. printf("timed clamp is timeout\n");
  788. return false;
  789. }
  790. if(timed_clamp_.Get()==eOpened)
  791. return true;
  792. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  793. monitor_->clamp_open(move_mode_);
  794. actionType_=eClampOpen;
  795. }
  796. return false;
  797. }
  798. return false;
  799. }
  800. Navigation::MpcResult Navigation::MpcToTarget(NavMessage::PathNode node,stLimit limit_v,bool autoDirect) {
  801. if (IsArrived(node)) {
  802. printf(" current already in target completed !!!\n");
  803. return eMpcSuccess;
  804. }
  805. if (inited_ == false) {
  806. printf(" navigation has not inited\n");
  807. return eMpcFailed;
  808. }
  809. if (PoseTimeout()) {
  810. printf(" navigation Error:Pose is timeout \n");
  811. return eMpcFailed;
  812. }
  813. Pose2d current=timedPose_.Get();
  814. Pose2d target(node.x(),node.y(),0);
  815. //生成轨迹
  816. Trajectory traj = Trajectory::create_line_trajectory(current, target);
  817. if (traj.size() == 0)
  818. return eMpcSuccess;
  819. //判断 巡线方向
  820. bool directY=false;
  821. if(autoDirect){
  822. Pose2d target_relative=Pose2d::relativePose(target,timedPose_.Get());
  823. if( fabs(target_relative.y())>fabs(target_relative.x())) { //目标轨迹点在当前点Y轴上
  824. std::cout<<" MPC Y axis target_relative:"<<target_relative<<std::endl;
  825. directY = true;
  826. }else{
  827. std::cout<<" MPC X axis target_relative:"<<target_relative<<std::endl;
  828. }
  829. }
  830. printf(" exec along autoDirect:%d\n",autoDirect);
  831. while (cancel_ == false) {
  832. std::this_thread::sleep_for(std::chrono::milliseconds(50));
  833. if (pause_ == true) {
  834. //发送暂停消息
  835. continue;
  836. }
  837. if (PoseTimeout()) {
  838. printf(" navigation Error:Pose is timeout \n");
  839. return eMpcFailed;
  840. }
  841. if(timedV_.timeout() || timedA_.timeout()){
  842. printf(" navigation Error:v/a is timeout \n");
  843. return eMpcFailed;
  844. }
  845. //判断是否到达终点
  846. if (IsArrived(node)) {
  847. if (Stop()) {
  848. printf(" exec along completed !!!\n");
  849. return eMpcSuccess;
  850. }
  851. }
  852. //一次变速
  853. std::vector<double> out;
  854. bool ret;
  855. TimerRecord::Execute([&, this]() {
  856. ret = mpc_once(traj, limit_v, out,directY);
  857. }, "mpc_once");
  858. if (ret == false) {
  859. Stop();
  860. return eMpcFailed;
  861. }
  862. /*
  863. * AGV 在终点附近低速巡航时,设置最小速度0.05
  864. */
  865. Pose2d target_in_agv=Pose2d::relativePose(target,timedPose_.Get());
  866. if (directY) {
  867. target_in_agv=target_in_agv.rotate(M_PI / 2.0);
  868. }
  869. if(Pose2d::abs(target_in_agv)<Pose2d(0.2,2,M_PI*2)) {
  870. if (out[0] >= 0 && out[0] < limit_v.min)
  871. out[0] = limit_v.min;
  872. if (out[0] < 0 && out[0] > -limit_v.min)
  873. out[0] = -limit_v.min;
  874. }
  875. //下发速度
  876. if(directY==false)
  877. SendMoveCmd(move_mode_, Monitor_emqx::eVertical, out[0], out[1]);
  878. else
  879. SendMoveCmd(move_mode_, Monitor_emqx::eHorizontal, out[0], out[1]);
  880. actionType_=directY?eHorizon:eVertical;
  881. /*
  882. * 判断车辆是否在终点附近徘徊,无法到达终点
  883. */
  884. if (PossibleToTarget(node, directY) == false) {
  885. printf(" --------------MPC imposible to target -------------------------------------------\n");
  886. if(fabs(timedV_.Get())>0.1 || fabs(timedA_.Get())>10*M_PI/180.0)
  887. SlowlyStop();
  888. else
  889. Stop();
  890. return eImpossibleToTarget;
  891. }
  892. }
  893. return eMpcFailed;
  894. }
  895. bool Navigation::PossibleToTarget(NavMessage::PathNode targetNode,bool directY) {
  896. if (timedPose_.timeout()) {
  897. return false;
  898. }
  899. Pose2d current = timedPose_.Get();
  900. double tx = targetNode.x();
  901. double ty = targetNode.y();
  902. double l = fabs(targetNode.l());
  903. double w = fabs(targetNode.w());
  904. double theta = -targetNode.theta();
  905. double W = 2.45;
  906. double L = 1.3;
  907. double minYaw=5*M_PI/180.0;
  908. if(move_mode_==Monitor_emqx::eMain){
  909. L=1.3+2.7;
  910. }
  911. if(directY){
  912. current=current.rotate(current.x(),current.y(),M_PI/2);
  913. double t=W;
  914. W=L;
  915. L=t;
  916. }
  917. double minR = W / 2 + L / tan(minYaw);
  918. //printf("l:%f,w:%f\n",l,w);
  919. std::vector<Pose2d> poses = Pose2d::generate_rectangle_vertexs(Pose2d(tx, ty, 0), l*2, w*2);
  920. bool nagY=false;
  921. bool posiY=false;
  922. for (int i = 0; i < poses.size(); ++i) {
  923. Pose2d rpos = poses[i].rotate(tx, ty, theta);
  924. Pose2d relative=Pose2d::relativePose(rpos,current);
  925. double ax =fabs(relative.x());
  926. double ay = fabs(relative.y());
  927. if(relative.y()>0) posiY=true;
  928. if(relative.y()<0) nagY=true;
  929. if (ax * ax + pow(ay - minR, 2) > minR*minR) {
  930. /*printf(" possible to target:%f %f l:%f,w:%f theta:%f minR:%f ax:%f,ay:%f\n",
  931. targetNode.x(),targetNode.y(),targetNode.l(),targetNode.w(),targetNode.theta(),
  932. minR,ax,ay);*/
  933. return true;
  934. }else if(nagY&&posiY){
  935. return true;
  936. }
  937. printf("directY:%d targetInPose:%f %f l:%f,w:%f theta:%f minR:%f ax:%f,ay:%f\n",directY,
  938. relative.x(),relative.y(),targetNode.l(),targetNode.w(),targetNode.theta(),
  939. minR,ax,ay);
  940. }
  941. printf(" impossible to target:%f %f l:%f,w:%f theta:%f\n",
  942. targetNode.x(),targetNode.y(),targetNode.l(),targetNode.w(),targetNode.theta());
  943. return false;
  944. }
  945. void Navigation::navigatting() {
  946. if (inited_ == false) {
  947. printf(" navigation has not inited\n");
  948. return;
  949. }
  950. pause_ = false;
  951. cancel_ = false;
  952. running_ = true;
  953. actionType_ = eReady;
  954. printf(" navigation beg...\n");
  955. while (newUnfinished_cations_.empty() == false && cancel_ == false) {
  956. std::cout << "unfinished size:" << newUnfinished_cations_.size() << std::endl;
  957. NavMessage::NewAction act = newUnfinished_cations_.front();
  958. if(act.type()==1){ //入库
  959. space_id_=act.spacenode().id();
  960. isInSpace_=true;
  961. if(!execute_InOut_space(act)){
  962. printf(" In space failed\n");
  963. break;
  964. }
  965. }
  966. else if(act.type()==2){ //出库
  967. if(!execute_InOut_space(act)){
  968. printf(" out space failed\n");
  969. break;
  970. }else{
  971. isInSpace_=false;
  972. }
  973. }else if (act.type() == 3 || act.type() == 4) { //马路导航
  974. if (!execute_nodes(act))
  975. break;
  976. }else if(act.type()==5){
  977. printf(" 汽车模型导航....\n");
  978. }else if (act.type() == 6) {//夹持
  979. if (this->clamp_close() == false) {
  980. printf("夹持failed ...\n");
  981. break;
  982. }
  983. } else if (act.type() == 7) {
  984. if (this->clamp_open() == false) {
  985. printf("打开夹持 failed...\n");
  986. break;
  987. }
  988. } else if(act.type()==8){ //切换模式
  989. SwitchMode(Monitor_emqx::ActionMode(act.changedmode()),act.wheelbase());
  990. }else{
  991. printf(" action type invalid not handled !!\n");
  992. break;
  993. }
  994. newUnfinished_cations_.pop();
  995. }
  996. actionType_ = eReady;
  997. Stop();
  998. if (cancel_ == true) {
  999. printf(" navigation canceled\n");
  1000. while (newUnfinished_cations_.empty() == false)
  1001. newUnfinished_cations_.pop();
  1002. } else {
  1003. if (newUnfinished_cations_.empty())
  1004. printf("navigation completed!!!\n");
  1005. else {
  1006. printf(" navigation Failed\n");
  1007. while (newUnfinished_cations_.empty() == false)
  1008. newUnfinished_cations_.pop();
  1009. }
  1010. }
  1011. running_ = false;
  1012. }
  1013. void Navigation::SwitchMode(Monitor_emqx::ActionMode mode,float wheelBase){
  1014. printf("Child AGV can not Switch Mode\n");
  1015. }
  1016. float Navigation::compute_cuv(const Pose2d& target)
  1017. {
  1018. float x=fabs(target.x());
  1019. float y=fabs(target.y());
  1020. float cuv= atan(y/(x+1e-8));
  1021. //printf(" ---------------------- cuv:%f\n",cuv);
  1022. return cuv;
  1023. }