navigation.cpp 32 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037
  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=0.1)
  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. //发布nav状态
  158. statu.set_statu(actionType_); //
  159. //printf(" statu:%d\n",actionType_);
  160. statu.set_move_mode(move_mode_);
  161. if (running_)
  162. {
  163. statu.set_key(global_navCmd_.key());
  164. }
  165. //发布MPC信息
  166. //发布mpc 预选点
  167. if (selected_traj_.timeout() == false) {
  168. for (int i = 0; i < selected_traj_.Get().size(); ++i) {
  169. Pose2d pt = selected_traj_.Get()[i];
  170. NavMessage::Pose2d *pose = statu.mutable_selected_traj()->add_poses();
  171. pose->set_x(pt.x());
  172. pose->set_y(pt.y());
  173. pose->set_theta(pt.theta());
  174. }
  175. }
  176. //发布 mpc 预测点
  177. if (predict_traj_.timeout() == false) {
  178. for (int i = 0; i < predict_traj_.Get().size(); ++i) {
  179. Pose2d pt = predict_traj_.Get()[i];
  180. NavMessage::Pose2d *pose = statu.mutable_predict_traj()->add_poses();
  181. pose->set_x(pt.x());
  182. pose->set_y(pt.y());
  183. pose->set_theta(pt.theta());
  184. }
  185. }
  186. //std::cout<<"nav statu:"<<statu.DebugString()<<std::endl;
  187. MqttMsg msg;
  188. msg.fromProtoMessage(statu);
  189. if(terminator_)
  190. terminator_->Publish(parameter_.terminal_emqx().pubnavstatutopic(),msg);
  191. //发布位姿 ------robot状态--------------------------
  192. NavMessage::RobotStatu robot;
  193. if(CreateRobotStatuMsg(robot)) {
  194. if (terminator_) {
  195. MqttMsg msg;
  196. msg.fromProtoMessage(robot);
  197. terminator_->Publish(parameter_.terminal_emqx().pubstatutopic(), msg);
  198. }
  199. }
  200. }
  201. bool Navigation::CreateRobotStatuMsg(NavMessage::RobotStatu& robotStatu)
  202. {
  203. //printf(" %d %d %d \n",timedPose_.timeout(),timedV_.timeout(),timedA_.timeout());
  204. if (timedPose_.timeout() == false) {
  205. Pose2d pose = timedPose_.Get();
  206. robotStatu.set_x(pose.x());
  207. robotStatu.set_y(pose.y());
  208. robotStatu.set_theta(pose.theta());
  209. if((timedV_.timeout() == false && timedA_.timeout() == false)) {
  210. NavMessage::AgvStatu plc;
  211. plc.set_v(timedV_.Get());
  212. plc.set_w(timedA_.Get());
  213. plc.set_clamp(timed_clamp_.Get());
  214. //printf(" timed_clamp_:%d\n ",timed_clamp_.Get());
  215. robotStatu.mutable_agvstatu()->CopyFrom(plc);
  216. }
  217. return true;
  218. }
  219. return false;
  220. }
  221. void Navigation::ResetStatu(double v,double a)
  222. {
  223. timedV_.reset(v,0.5);
  224. timedA_.reset(a,0.5);
  225. }
  226. void Navigation::ResetClamp(ClampStatu statu){
  227. timed_clamp_.reset(statu,1);
  228. }
  229. void Navigation::ResetPose(const Pose2d& pose)
  230. {
  231. timedPose_.reset(pose,1.0);
  232. }
  233. bool Navigation::Start(const NavMessage::NavCmd& cmd)
  234. {
  235. if(newUnfinished_cations_.empty()==false) //正在运行中,上一次指令未完成
  236. {
  237. if(pause_)
  238. {
  239. pause_=false;
  240. return true;
  241. }
  242. printf(" navigation is running pls cancel before\n");
  243. return false;
  244. }
  245. if(thread_!= nullptr)
  246. {
  247. if(thread_->joinable())
  248. thread_->join();
  249. delete thread_;
  250. }
  251. //add 先检查当前点与起点的距离
  252. global_navCmd_=cmd;
  253. for (int i = 0; i < cmd.newactions_size(); ++i)
  254. newUnfinished_cations_.push(cmd.newactions(i));
  255. thread_=new std::thread(&Navigation::navigatting,this);
  256. return true;
  257. }
  258. void Navigation::Cancel()
  259. {
  260. cancel_=true;
  261. }
  262. bool Navigation::Stop() {
  263. if(monitor_)
  264. {
  265. monitor_->stop();
  266. while(cancel_==false)
  267. {
  268. if(timedV_.timeout()==false && timedA_.timeout()==false)
  269. {
  270. if(fabs(timedV_.Get())<1e-2 && fabs(timedA_.Get())<1e-3)
  271. return true;
  272. else
  273. monitor_->stop();
  274. printf("Stoped wait V/A ==0(1e-4,1e-4),V:%f,A:%f\n",fabs(timedV_.Get()),fabs(timedA_.Get()));
  275. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  276. }else{
  277. printf("Stop failed V/A timeout\n");
  278. return false;
  279. }
  280. }
  281. }
  282. printf("stoped ret false.\n");
  283. return false;
  284. }
  285. void Navigation::Pause()
  286. {
  287. if(Stop())
  288. pause_=true;
  289. }
  290. Navigation::Navigation()
  291. {
  292. move_mode_=Monitor_emqx::eSingle;
  293. thread_= nullptr;
  294. monitor_= nullptr;
  295. terminator_= nullptr;
  296. timedBrotherPose_.reset(Pose2d(-100,0,0),0.1);
  297. }
  298. void Navigation::BrotherAgvStatuCallback(const MqttMsg& msg,void* context)
  299. {
  300. Navigation* navigator=(Navigation*)context;
  301. NavMessage::LidarOdomStatu brother_statu;
  302. if(msg.toProtoMessage(brother_statu)==false) {
  303. std::cout<<" msg transform to AGVStatu failed,msg:"<<msg.data()<<std::endl;
  304. return;
  305. }
  306. //std::cout<<brother_nav.DebugString()<<std::endl<<std::endl;
  307. Pose2d pose(brother_statu.x(),brother_statu.y(),brother_statu.theta());
  308. navigator->timedBrotherPose_.reset(pose,1);
  309. navigator->timedBrotherV_.reset(brother_statu.v(),1);
  310. navigator->timedBrotherA_.reset(brother_statu.vth(),1);
  311. }
  312. void Navigation::HandleNavCmd(const NavMessage::NavCmd& cmd)
  313. {
  314. if(cmd.action()==3)
  315. {
  316. printf(" Nav cancel\n");
  317. Cancel();
  318. return ;
  319. }
  320. if(cmd.action()==2) {
  321. printf(" Nav continue\n");
  322. pause_=false;
  323. return ;
  324. }
  325. if(cmd.action()==1) {
  326. printf(" Nav pause\n");
  327. Pause();
  328. return ;
  329. }
  330. if(cmd.action()==0||cmd.action()==6)
  331. {
  332. Start(cmd);
  333. }
  334. else
  335. printf(" Invalid action ,action:%d\n",cmd.action());
  336. }
  337. void Navigation::NavCmdCallback(const MqttMsg& msg,void* context)
  338. {
  339. NavMessage::NavCmd cmd;
  340. if(msg.toProtoMessage(cmd)==false) {
  341. printf(" msg transform to NavCmd failed ..!!\n");
  342. return;
  343. }
  344. Navigation* navigator=(Navigation*)context;
  345. navigator->HandleNavCmd(cmd);
  346. }
  347. bool Navigation::execute_adjust_action(const Pose2d& target,const Pose2d& target_diff,stLimit limit_v,
  348. stLimit limit_h,stLimit limit_rotate,bool anyDitect)
  349. {
  350. std::cout<<" adjust target:"<<target<<" target diff:"<<target_diff<<std::endl;
  351. if(inited_==false) {
  352. printf(" navigation has not inited\n");
  353. return false;
  354. }
  355. Pose2d accuracy=target_diff.rotate(timedPose_.Get().theta());
  356. Pose2d thresh=Pose2d::abs(accuracy);
  357. int action=0; //1 原地旋转,2横移,3前进
  358. while(cancel_==false) {
  359. std::this_thread::sleep_for(std::chrono::milliseconds(50));
  360. if (pause_ == true) {
  361. //发送暂停消息
  362. continue;
  363. }
  364. if (PoseTimeout() || timedV_.timeout() || timedA_.timeout()) {
  365. printf(" navigation Error:Pose/v/a is timeout \n");
  366. break;
  367. }
  368. //判断是否到达目标点
  369. int direct=0;
  370. if(anyDitect) direct=2;
  371. if (IsArrived(timedPose_.Get(), timedV_.Get(), timedA_.Get(), target, accuracy,direct)) {
  372. if(Stop()) {
  373. printf("adjust completed anyDitect :%d\n",anyDitect);
  374. return true;
  375. }
  376. return false;
  377. }
  378. //计算目标点在当前pose下的pose
  379. Pose2d diff = Pose2d::relativePose(target,timedPose_.Get());
  380. //停止状态
  381. if (action == 0) {
  382. //
  383. if (Pose2d::abs(diff).x() > thresh.x()) {
  384. //前进
  385. action = 3;
  386. }else if (Pose2d::abs(diff).y() > thresh.y()) {
  387. //横移
  388. action = 2;
  389. }
  390. else if (Pose2d::abs(diff).theta() > thresh.theta()) {
  391. action = 1; //原地旋转
  392. }
  393. }
  394. else
  395. {
  396. double acc_v=0.6;
  397. double acc_angular=10.0*M_PI/180.0;
  398. double dt=0.1;
  399. if (action == 1) {
  400. float minYawDiff=diff.theta();
  401. if(anyDitect){
  402. Pose2d p0=timedPose_.Get();
  403. float yawdiff[4]={0};
  404. yawdiff[0]=diff.theta();
  405. yawdiff[1]=Pose2d::relativePose(target,p0-Pose2d(0,0,M_PI/2)).theta(); ////使用减法,保证角度在【-pi pi】
  406. yawdiff[2]=Pose2d::relativePose(target,p0-Pose2d(0,0,M_PI)).theta();
  407. yawdiff[3]=Pose2d::relativePose(target,p0-Pose2d(0,0,3*M_PI/2)).theta();
  408. for(int i=1;i<4;++i){
  409. if(fabs(yawdiff[i])<fabs(minYawDiff)){
  410. minYawDiff=yawdiff[i];
  411. }
  412. }
  413. }
  414. if (fabs(minYawDiff) > thresh.theta()) {
  415. double theta = limit_gause(minYawDiff,limit_rotate.min,limit_rotate.max);
  416. double angular=next_speed(timedA_.Get(),theta,acc_angular,dt);
  417. double limit_angular=limit(angular,limit_rotate.min,limit_rotate.max);
  418. SendMoveCmd(move_mode_,Monitor_emqx::eRotate, 0, limit_angular);
  419. actionType_=eRotation;
  420. printf(" Ratate | input anguar:%f,next angular:%f,down:%f diff:%f anyDitect:%d\n",
  421. timedA_.Get(),angular,limit_angular,minYawDiff,anyDitect);
  422. continue;
  423. }
  424. }
  425. if (action == 2) {
  426. if (Pose2d::abs(diff).y() > thresh.y()) {
  427. double hv=limit_gause(diff.y(),limit_h.min,limit_h.max);
  428. double velocity=limit(next_speed(timedV_.Get(),hv,acc_v,dt),limit_h.min,limit_h.max);
  429. SendMoveCmd(move_mode_,Monitor_emqx::eHorizontal,velocity , 0);
  430. actionType_=eHorizon;
  431. printf(" Horizontal input:%f out:%f\n",timedV_.Get(),velocity);
  432. continue;
  433. }
  434. }
  435. if (action == 3) {
  436. if (Pose2d::abs(diff).x() > thresh.x()) {
  437. double v=limit_gause(diff.x(),limit_v.min,limit_v.max);
  438. double velocity=limit(next_speed(timedV_.Get(),v,acc_v,dt),limit_v.min,limit_v.max);
  439. SendMoveCmd(move_mode_,Monitor_emqx::eMPC, velocity, 0);
  440. actionType_=eVertical;
  441. printf(" Vrtical input:%f,out:%f diff.x:%f\n",timedV_.Get(),velocity,diff.x());
  442. continue;
  443. }
  444. }
  445. if(Stop()) {
  446. printf(" monitor type :%d completed!!! reset action type!!!\n", action);
  447. action = 0;
  448. }
  449. }
  450. }
  451. return false;
  452. }
  453. bool Navigation::execute_nodes(NavMessage::NewAction action)
  454. {
  455. if(action.type()==3 || action.type()==4) //最优动作导航 or 导航中保证朝向严格一致
  456. {
  457. if(!action.has_nodevelocitylimit() || !action.has_nodeangularlimit()||
  458. !action.has_adjustvelocitylimit()|| !action.has_adjusthorizonlimit()
  459. || action.pathnodes_size()==0) {
  460. std::cout << "execute pathNodes failed ,Action invalid:" << action.DebugString() << std::endl;
  461. return false;
  462. }
  463. bool anyDirect=(action.type()==3);
  464. //速度限制
  465. stLimit adjust_x={ action.adjustvelocitylimit().min(),action.adjustvelocitylimit().max() };
  466. stLimit adjust_h={ action.adjusthorizonlimit().min(),action.adjusthorizonlimit().max() };
  467. stLimit adjust_angular={ action.nodeangularlimit().min(),action.nodeangularlimit().max() };
  468. stLimit mpc_velocity={ action.nodevelocitylimit().min(),action.nodevelocitylimit().max() };
  469. /*原地调整起点
  470. NavMessage::PathNode first=action.pathnodes(0);
  471. //目标,精度
  472. double first_yaw=timedPose_.Get().theta();
  473. if(1<action.pathnodes_size()){
  474. NavMessage::PathNode next=action.pathnodes(1);
  475. first_yaw=Pose2d::vector2yaw(next.pose().x()-first.pose().x(),next.pose().y()-first.pose().y());
  476. }
  477. Pose2d first_target(first.pose().x(),first.pose().y(),first_yaw);
  478. Pose2d first_accuracy(first.accuracy().x(),first.accuracy().y(),first.accuracy().theta());
  479. execute_adjust_action(first_target,first_accuracy,adjust_x,adjust_h,adjust_angular,anyDirect);
  480. Pose2d last_node=first_target;*/
  481. for(int i=1;i< action.pathnodes_size();++i)
  482. {
  483. NavMessage::PathNode node = action.pathnodes(i);
  484. /// 巡线到目标点,判断巡线方向
  485. Pose2d target(node.pose().x(), node.pose().y(), node.pose().theta());
  486. Pose2d accuracy(node.accuracy().x(), node.accuracy().y(), node.accuracy().theta());
  487. while(cancel_==false){
  488. MpcResult ret=execute_along_action(timedPose_.Get(), target, accuracy, mpc_velocity, anyDirect);
  489. if(ret==eMpcSuccess){
  490. std::cout<<" MPC to target "<<target<<" completed"<<std::endl;
  491. break;
  492. }else if(ret==eImpossibleToTarget){
  493. std::cout<<" MPC to target "<<target<<" failed,retry"<<std::endl;
  494. }else{
  495. return false;
  496. }
  497. }
  498. if(cancel_){
  499. return false;
  500. }
  501. }
  502. return true;
  503. }
  504. printf("execute PathNode failed ,action type is not 3/4 :%d\n",action.type());
  505. return false;
  506. }
  507. bool Navigation::execute_vehicle_mode(NavMessage::NewAction action){
  508. if(action.type()==5 ) //最优动作导航 or 导航中保证朝向严格一致
  509. {
  510. if (!action.has_nodevelocitylimit() || !action.has_nodeangularlimit() ||
  511. !action.has_adjustvelocitylimit() || !action.has_adjusthorizonlimit()
  512. || action.pathnodes_size() == 0) {
  513. std::cout << "execute pathNodes failed ,Action invalid:" << action.DebugString() << std::endl;
  514. return false;
  515. //原地调整起点
  516. NavMessage::PathNode first=action.pathnodes(0);
  517. //速度限制
  518. stLimit adjust_x={ action.adjustvelocitylimit().min(),action.adjustvelocitylimit().max() };
  519. stLimit adjust_h={ action.adjusthorizonlimit().min(),action.adjusthorizonlimit().max() };
  520. stLimit adjust_angular={ action.nodeangularlimit().min(),action.nodeangularlimit().max() };
  521. stLimit mpc_velocity={ action.nodevelocitylimit().min(),action.nodevelocitylimit().max() };
  522. //目标,精度
  523. double first_yaw=timedPose_.Get().theta();
  524. if(1<action.pathnodes_size()){
  525. NavMessage::PathNode next=action.pathnodes(1);
  526. first_yaw=Pose2d::vector2yaw(next.pose().x()-first.pose().x(),next.pose().y()-first.pose().y());
  527. }
  528. Pose2d first_target(first.pose().x(),first.pose().y(),first_yaw);
  529. Pose2d first_accuracy(first.accuracy().x(),first.accuracy().y(),first.accuracy().theta());
  530. //execute_adjust_action(first_target,first_accuracy,adjust_x,adjust_h,adjust_angular,anyDirect);
  531. return false;
  532. }
  533. }else{
  534. return false;
  535. }
  536. }
  537. bool Navigation::execute_InOut_space(NavMessage::NewAction action) {
  538. if (action.type() != 1 && action.type() != 2) {
  539. printf(" Inout_space failed : msg action type must ==1\n ");
  540. return false;
  541. }
  542. if (!action.has_inoutvlimit() || !action.has_spacenode() ||
  543. !action.has_streetnode()) {
  544. std::cout << "execute enter_space failed ,Action miss some infos:" << action.DebugString() << std::endl;
  545. return false;
  546. }
  547. if (PoseTimeout() == true) {
  548. printf(" inout_space failed type:%d : current pose is timeout\n", action.type());
  549. return false;
  550. }
  551. Pose2d begin, target, begin_accuracy, target_accuracy;
  552. //入库,起点为streetNode
  553. begin = Pose2d(action.streetnode().pose().x(), action.streetnode().pose().y(), action.streetnode().pose().theta());
  554. begin_accuracy = Pose2d(action.streetnode().accuracy().x(),
  555. action.streetnode().accuracy().y(),
  556. action.streetnode().accuracy().theta());
  557. target = Pose2d(action.spacenode().pose().x(), action.spacenode().pose().y(), action.spacenode().pose().theta());
  558. //目标点精度
  559. target_accuracy = Pose2d(action.spacenode().accuracy().x()*2,
  560. action.spacenode().accuracy().y()*2,
  561. action.spacenode().accuracy().theta()*2);
  562. double yaw = Pose2d::vector2yaw(target.x() - begin.x(), target.y() - begin.y());
  563. if (action.type() == 2) { //出库起点终点对调
  564. Pose2d mid = target;
  565. Pose2d mid_accuracy = target_accuracy;
  566. target = begin;
  567. target_accuracy = begin_accuracy;
  568. begin = mid;
  569. begin_accuracy = mid_accuracy;
  570. yaw = Pose2d::vector2yaw(begin.x() - target.x(), begin.y() - target.y());
  571. }
  572. //给起点赋予朝向,保证agv以正对车位的方向行进
  573. begin.mutable_theta() = yaw;
  574. //严格调整到起点
  575. stLimit adjust_x = {0.05, 0.2};
  576. stLimit adjust_h = {0.05, 0.2};
  577. stLimit adjust_angular = {2 * M_PI / 180.0, 20 * M_PI / 180.0};
  578. stLimit mpc_velocity = {0.05, 0.3};
  579. //判断当前点与起点的距离
  580. Pose2d distance(1, 1, M_PI * 2);
  581. if (action.type() == 2) { //出库要求起点距离当前点非常近
  582. distance = Pose2d(1, 0.1, 3 * M_PI);
  583. adjust_x = {0.03, 0.1};
  584. adjust_h = {0.03, 0.1};
  585. adjust_angular = {2 * M_PI / 180.0, 5 * M_PI / 180.0};
  586. }
  587. Pose2d relativeDiff=Pose2d::relativePose(begin,timedPose_.Get());
  588. if (!(Pose2d::abs(relativeDiff) < distance)) {
  589. printf(" Inout space failed type:%d: current pose too far from begin node\n", action.type());
  590. std::cout << " begin:" << begin << " current:" << timedPose_.Get()<<" relative:"<<relativeDiff << std::endl;
  591. return false;
  592. }
  593. if (action.type() == 1) //1,进库,先调整到库位前方(起点)
  594. if (execute_adjust_action(begin, begin_accuracy, adjust_x, adjust_h, adjust_angular, true) == false)
  595. return false;
  596. if (execute_along_action(begin, target, target_accuracy, mpc_velocity, true) == false)
  597. return false;
  598. return true;
  599. }
  600. bool Navigation::mpc_once(Trajectory traj,stLimit limit_v,std::vector<double>& out,bool directY) {
  601. if (PoseTimeout() == true) {
  602. printf(" MPC once Error:Pose is timeout \n");
  603. return false;
  604. }
  605. if(timedV_.timeout() == true || timedA_.timeout() == true){
  606. printf(" MPC once Error:V/A is timeout \n");
  607. return false;
  608. }
  609. if (traj.size() == 0) {
  610. printf("traj size ==0\n");
  611. return false;
  612. }
  613. Pose2d pose = timedPose_.Get();
  614. double velocity = timedV_.Get(); //从plc获取状态
  615. double angular = timedA_.Get();
  616. Eigen::VectorXd statu = Eigen::VectorXd::Zero(5);//agv状态
  617. statu[0] = pose.x();
  618. statu[1] = pose.y();
  619. statu[2] = pose.theta();
  620. statu[3] = velocity;
  621. statu[4] = angular;
  622. Trajectory optimize_trajectory;
  623. Trajectory selected_trajectory;
  624. NavParameter::MPC_parameter mpc_parameter=parameter_.x_mpc_parameter();
  625. double obs_w=0.85;
  626. double obs_h=1.45;
  627. if (directY == true) {
  628. //将车身朝向旋转90°,车身朝向在(-pi,pi]
  629. statu[2] += M_PI / 2;
  630. if (statu[2] > M_PI)
  631. statu[2] -= 2 * M_PI;
  632. mpc_parameter=parameter_.y_mpc_parameter();
  633. obs_w=1.45;
  634. obs_h=0.85;
  635. }
  636. Pose2d brother = timedBrotherPose_.Get();
  637. Pose2d relative = Pose2d::relativePose(brother, pose);
  638. if(directY)
  639. relative = Pose2d::relativePose(brother.rotate(brother.x(),brother.y(),M_PI/2), pose.rotate(pose.x(),pose.y(),M_PI/2));//计算另一节在当前小车坐标系下的坐标
  640. std::cout<<"pose:"<<pose<<", brother:"<<brother<<", relative:"<<relative<<std::endl;
  641. if (move_mode_ == Monitor_emqx::ActionMode::eMain)
  642. relative = Pose2d(-1e8, -1e8, 0);
  643. MpcError ret = failed;
  644. LoadedMPC MPC(relative, obs_w,obs_h,limit_v.min, limit_v.max);
  645. LoadedMPC::MPC_parameter parameter={mpc_parameter.shortest_radius(),mpc_parameter.dt(),
  646. mpc_parameter.acc_velocity(),mpc_parameter.acc_angular()};
  647. //printf(" r:%f dt:%f acc:%f acc_a:%f\n",mpc_parameter.shortest_radius(),
  648. // mpc_parameter.dt(),mpc_parameter.acc_velocity(),mpc_parameter.acc_angular());
  649. ret = MPC.solve(traj, traj[traj.size() - 1], statu,parameter,
  650. out, selected_trajectory, optimize_trajectory);
  651. //std::cout<<" traj size %d %d -------- "<<selected_trajectory.size()<<","<<optimize_trajectory.size()<<std::endl;
  652. if(ret==no_solution) {
  653. printf(" mpc solve no solution set v/w = 0\n");
  654. out.clear();
  655. out.push_back(0);
  656. out.push_back(0);
  657. }
  658. predict_traj_.reset(optimize_trajectory, 1);
  659. selected_traj_.reset(selected_trajectory, 1);
  660. return ret==success || ret==no_solution;
  661. }
  662. bool Navigation::IsArrived(const Pose2d& cur,double velocity,double angular,
  663. const Pose2d& target,const Pose2d& diff,int direct)
  664. {
  665. //std::cout<<cur<<","<<target<<","<<nearest_yaw<<",v"<<velocity<<"a:"<<angular<<"diff:"<<diff<<std::endl;
  666. Pose2d distance=Pose2d::relativePose(target,cur);
  667. Pose2d absDiff=Pose2d::abs(distance);
  668. //std::cout<<" arrive distanc:"<<distance<<",direct:"<<direct<<std::endl;
  669. if(direct==1){ //纵向MPC
  670. if(absDiff.x()<diff.x() && absDiff.y()<diff.y())
  671. {
  672. float diffYaw=absDiff.theta(); //[0-pi)
  673. float diffYaw2=absDiff.theta()-M_PI;
  674. bool yawArrived=( fabs(diffYaw)<diff.theta() || fabs(diffYaw2)<diff.theta() );
  675. if(yawArrived && fabs(velocity) < 0.06 && fabs(angular) < 5 * M_PI / 180.0)
  676. return true;
  677. }
  678. }else if(direct==2){ //横向MPC
  679. if(absDiff.x()<diff.x() && absDiff.y()<diff.y())
  680. {
  681. float diffYaw=absDiff.theta(); //[0-pi)
  682. float diffYaw1=absDiff.theta()-M_PI/2;
  683. float diffYaw2=absDiff.theta()-M_PI;
  684. float diffYaw3=absDiff.theta()-3*M_PI/2;
  685. printf(" diff 123 :%f %f %f %f\n",diffYaw,diffYaw1,diffYaw2,diffYaw3);
  686. bool yawArrived=( fabs(diffYaw)<diff.theta() || fabs(diffYaw1)<diff.theta()
  687. || fabs(diffYaw2)<diff.theta() ||fabs(diffYaw3)<diff.theta() );
  688. if(yawArrived && fabs(velocity) < 0.06 && fabs(angular) < 5 * M_PI / 180.0)
  689. return true;
  690. }
  691. }else{ //原地调整
  692. if (absDiff < diff) {
  693. if (fabs(velocity) < 0.03 && fabs(angular) < 5 * M_PI / 180.0)
  694. return true;
  695. }
  696. }
  697. //std::cout<<"distance:"<<distance<<" diff:"<<diff<<" v:"<<velocity<<" a:"<<angular<<std::endl;
  698. return false;
  699. }
  700. void Navigation::SendMoveCmd(Monitor_emqx::ActionMode mode,Monitor_emqx::ActionType type,
  701. double v,double angular){
  702. if(monitor_) {
  703. monitor_->set_speed(mode, type, v, angular);
  704. }
  705. }
  706. bool Navigation::clamp_close()
  707. {
  708. if(monitor_) {
  709. printf("Clamp closing...\n");
  710. monitor_->clamp_close(move_mode_);
  711. actionType_=eClampClose;
  712. while (cancel_ == false) {
  713. if (timed_clamp_.timeout()) {
  714. printf("timed clamp is timeout\n");
  715. return false;
  716. }
  717. if (timed_clamp_.Get() == eClosed)
  718. return true;
  719. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  720. monitor_->clamp_close(move_mode_);
  721. actionType_=eClampClose;
  722. }
  723. return false;
  724. }
  725. return false;
  726. }
  727. bool Navigation::clamp_open() {
  728. if(monitor_) {
  729. printf("Clamp openning...\n");
  730. monitor_->clamp_open(move_mode_);
  731. actionType_=eClampOpen;
  732. while(cancel_==false)
  733. {
  734. if(timed_clamp_.timeout())
  735. {
  736. printf("timed clamp is timeout\n");
  737. return false;
  738. }
  739. if(timed_clamp_.Get()==eOpened)
  740. return true;
  741. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  742. monitor_->clamp_open(move_mode_);
  743. actionType_=eClampOpen;
  744. }
  745. return false;
  746. }
  747. return false;
  748. }
  749. Navigation::MpcResult Navigation::execute_along_action(const Pose2d& begin,const Pose2d& target,const Pose2d& target_diff,
  750. stLimit limit_v,bool autoDirect) {
  751. if (inited_ == false) {
  752. printf(" navigation has not inited\n");
  753. return eMpcFailed;
  754. }
  755. if (PoseTimeout()) {
  756. printf(" navigation Error:Pose is timeout \n");
  757. return eMpcFailed;
  758. }
  759. //生成轨迹
  760. Trajectory traj = Trajectory::create_line_trajectory(begin, target);
  761. if (traj.size() == 0)
  762. return eMpcSuccess;
  763. //判断 巡线方向
  764. bool directY=false;
  765. if(autoDirect){
  766. Pose2d target_relative=Pose2d::relativePose(target,timedPose_.Get());
  767. if( fabs(target_relative.y())>fabs(target_relative.x())) { //目标轨迹点在当前点Y轴上
  768. std::cout<<" MPC Y axis target_relative:"<<target_relative<<std::endl;
  769. directY = true;
  770. }else{
  771. std::cout<<" MPC X axis target_relative:"<<target_relative<<std::endl;
  772. }
  773. }
  774. printf(" exec along autoDirect:%d\n",autoDirect);
  775. while (cancel_ == false) {
  776. std::this_thread::sleep_for(std::chrono::milliseconds(50));
  777. if (pause_ == true) {
  778. //发送暂停消息
  779. continue;
  780. }
  781. if (PoseTimeout()) {
  782. printf(" navigation Error:Pose is timeout \n");
  783. return eMpcFailed;
  784. }
  785. if(timedV_.timeout() || timedA_.timeout()){
  786. printf(" navigation Error:v/a is timeout \n");
  787. return eMpcFailed;
  788. }
  789. //判断是否到达终点
  790. Pose2d target_accuracy=target_diff;
  791. if(directY)
  792. target_accuracy=Pose2d::abs(target_diff.rotate(timedPose_.Get().theta()));
  793. if (IsArrived(timedPose_.Get(), timedV_.Get(), timedA_.Get(), target, target_accuracy,2)) {
  794. if (Stop()) {
  795. printf(" exec along completed !!!\n");
  796. return eMpcSuccess;
  797. }
  798. }
  799. //一次变速
  800. std::vector<double> out;
  801. bool ret;
  802. TimerRecord::Execute([&, this]() {
  803. ret = mpc_once(traj, limit_v, out,directY);
  804. }, "mpc_once");
  805. if (ret == false) {
  806. Stop();
  807. return eMpcFailed;
  808. }
  809. /*
  810. * AGV 在终点附近低速巡航时,设置最小速度0.05
  811. */
  812. Pose2d target_in_agv=Pose2d::relativePose(target,timedPose_.Get());
  813. if (directY) {
  814. target_in_agv=target_in_agv.rotate(M_PI / 2.0);
  815. }
  816. if(Pose2d::abs(target_in_agv)<Pose2d(0.2,2,M_PI*2)) {
  817. if (out[0] >= 0 && out[0] < limit_v.min)
  818. out[0] = limit_v.min;
  819. if (out[0] < 0 && out[0] > -limit_v.min)
  820. out[0] = -limit_v.min;
  821. }
  822. //下发速度
  823. if(directY==false)
  824. SendMoveCmd(move_mode_, Monitor_emqx::eMPC, out[0], out[1]);
  825. else
  826. SendMoveCmd(move_mode_, Monitor_emqx::eHorizontal, out[0], out[1]);
  827. actionType_=eMPC;
  828. /*
  829. * 判断车辆是否在终点附近徘徊,无法到达终点
  830. */
  831. if (mpc_possible_to_end(target, target_accuracy,directY) == false) {
  832. printf(" --------------MPC imposible to target -----------------------\n");
  833. if(fabs(timedV_.Get())>0.1 || fabs(timedA_.Get())>5*M_PI/180.0)
  834. Stop();
  835. return eImpossibleToTarget;
  836. //调整到目标点
  837. /*stLimit limitv, limitR;
  838. limitv.min = 0.05;
  839. limitv.max = 0.1;
  840. limitR.min = 2 * M_PI / 180.0;
  841. limitR.max = 10 * M_PI / 180.0;
  842. Pose2d accuracy(target_diff.x(),target_diff.y(),M_PI*2);
  843. if (execute_adjust_action(target, accuracy, limitv, limitv, limitR,false))
  844. return true;
  845. else
  846. return false;*/
  847. }
  848. //std::this_thread::sleep_for(std::chrono::milliseconds (400));
  849. }
  850. return eMpcFailed;
  851. }
  852. bool Navigation::mpc_possible_to_end(const Pose2d& target,const Pose2d& target_diff,bool directY)
  853. {
  854. if(timedPose_.timeout()==false) {
  855. Pose2d current = timedPose_.Get();
  856. Pose2d targetInPose = Pose2d::relativePose(target, current);
  857. //std::cout<<" target in pose:"<<targetInPose<<", target diff:"<<target_diff<<std::endl;
  858. if (directY) {
  859. targetInPose=targetInPose.rotate(M_PI / 2.0);
  860. }
  861. if (fabs(targetInPose.x()) < target_diff.x()) {
  862. if (fabs(targetInPose.y()) > target_diff.y())
  863. return false;
  864. else
  865. return true;
  866. } else {
  867. return true;
  868. }
  869. }else{
  870. return false;
  871. }
  872. }
  873. void Navigation::navigatting() {
  874. if (inited_ == false) {
  875. printf(" navigation has not inited\n");
  876. return;
  877. }
  878. pause_ = false;
  879. cancel_ = false;
  880. running_ = true;
  881. actionType_ = eReady;
  882. printf(" navigation beg...\n");
  883. while (newUnfinished_cations_.empty() == false && cancel_ == false) {
  884. std::cout << "unfinished size:" << newUnfinished_cations_.size() << std::endl;
  885. NavMessage::NewAction act = newUnfinished_cations_.front();
  886. if(act.type()==1){ //入库
  887. if(!execute_InOut_space(act)){
  888. printf(" In space failed\n");
  889. break;
  890. }
  891. }
  892. else if(act.type()==2){ //出库
  893. if(!execute_InOut_space(act)){
  894. printf(" out space failed\n");
  895. break;
  896. }
  897. }else if (act.type() == 3 || act.type() == 4) { //马路导航
  898. if (!execute_nodes(act))
  899. break;
  900. }else if(act.type()==5){
  901. printf(" 汽车模型导航....\n");
  902. }else if (act.type() == 6) {//夹持
  903. if (this->clamp_close() == false) {
  904. printf("夹持failed ...\n");
  905. break;
  906. }
  907. } else if (act.type() == 7) {
  908. if (this->clamp_open() == false) {
  909. printf("打开夹持 failed...\n");
  910. break;
  911. }
  912. } else if(act.type()==8){ //切换模式
  913. SwitchMode(Monitor_emqx::ActionMode(act.changedmode()),act.wheelbase());
  914. }else{
  915. printf(" action type invalid not handled !!\n");
  916. break;
  917. }
  918. newUnfinished_cations_.pop();
  919. }
  920. actionType_ = eReady;
  921. Stop();
  922. if (cancel_ == true) {
  923. printf(" navigation canceled\n");
  924. while (newUnfinished_cations_.empty() == false)
  925. newUnfinished_cations_.pop();
  926. } else {
  927. if (newUnfinished_cations_.empty())
  928. printf("navigation completed!!!\n");
  929. else {
  930. printf(" navigation Failed\n");
  931. while (newUnfinished_cations_.empty() == false)
  932. newUnfinished_cations_.pop();
  933. }
  934. }
  935. running_ = false;
  936. }
  937. void Navigation::SwitchMode(Monitor_emqx::ActionMode mode,float wheelBase){
  938. printf("Child AGV can not Switch Mode\n");
  939. }