navigation.cpp 36 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142
  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=Pose2d::abs(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::RotateReferToTarget(const Pose2d& target,stLimit limit_rotate,bool anyDirect) {
  454. while(cancel_==false) {
  455. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  456. if (timedPose_.timeout()) {
  457. printf(" RotateBytarget failed pose timeout\n");
  458. return false;
  459. }
  460. if (timedA_.timeout()) {
  461. printf(" RotateBytarget failed wmg timeout\n");
  462. return false;
  463. }
  464. Pose2d targetInPose = Pose2d::relativePose(target, timedPose_.Get());
  465. float yawDiff = Pose2d::vector2yaw(targetInPose.x(), targetInPose.y());
  466. float minYawdiff = yawDiff;
  467. if (anyDirect) {
  468. Pose2d p0 = timedPose_.Get();
  469. float yawdiff[4] = {0};
  470. yawdiff[0] = yawDiff;
  471. Pose2d relativePose;
  472. relativePose = Pose2d::relativePose(target, p0 - Pose2d(0, 0, M_PI / 2));
  473. yawdiff[1] = Pose2d::vector2yaw(relativePose.x(), relativePose.y()); ////使用减法,保证角度在【-pi pi】
  474. relativePose = Pose2d::relativePose(target, p0 - Pose2d(0, 0, M_PI));
  475. yawdiff[2] = Pose2d::vector2yaw(relativePose.x(), relativePose.y());
  476. relativePose = Pose2d::relativePose(target, p0 - Pose2d(0, 0, 3 * M_PI / 2));
  477. yawdiff[3] = Pose2d::vector2yaw(relativePose.x(), relativePose.y());
  478. for (int i = 1; i < 4; ++i) {
  479. if (fabs(yawdiff[i]) < fabs(minYawdiff)) {
  480. minYawdiff = yawdiff[i];
  481. targetInPose=Pose2d::relativePose(target,p0-Pose2d(0,0,i*M_PI/2.0));
  482. }
  483. }
  484. }
  485. std::cout<<" Rotate refer to target:"<<target<<",targetInPose:"
  486. <<targetInPose<<",anyDirect:"<<anyDirect<<std::endl;
  487. //以当前点为原点,想方向经过目标点的二次曲线曲率>0.25,则需要调整 y=a x*x
  488. float cuv=compute_cuv(targetInPose);
  489. float dt=0.1;
  490. float acc_angular=15*M_PI/180.0;
  491. if (cuv>2*M_PI/180.0) {
  492. double theta = limit_gause(minYawdiff, limit_rotate.min, limit_rotate.max);
  493. double angular = next_speed(timedA_.Get(), theta, acc_angular, dt);
  494. double limit_angular = limit(angular, limit_rotate.min, limit_rotate.max);
  495. SendMoveCmd(move_mode_, Monitor_emqx::eRotate, 0, limit_angular);
  496. actionType_ = eRotation;
  497. printf(" Ratate | input anguar:%f,next angular:%f,down:%f diff:%f anyDitect:%d\n",
  498. timedA_.Get(), angular, limit_angular, minYawdiff, anyDirect);
  499. continue;
  500. }else{
  501. if(fabs(timedA_.Get())<5*M_PI/180.0) {
  502. printf(" Rotate refer target completed,cuv:%f\n", cuv);
  503. return true;
  504. }
  505. continue;
  506. }
  507. }
  508. return false;
  509. }
  510. bool Navigation::execute_nodes(NavMessage::NewAction action)
  511. {
  512. if(action.type()==3 || action.type()==4) //最优动作导航 or 导航中保证朝向严格一致
  513. {
  514. if(!action.has_nodevelocitylimit() || !action.has_nodeangularlimit()||
  515. !action.has_adjustvelocitylimit()|| !action.has_adjusthorizonlimit()
  516. || action.pathnodes_size()==0) {
  517. std::cout << "execute pathNodes failed ,Action invalid:" << action.DebugString() << std::endl;
  518. return false;
  519. }
  520. bool anyDirect=(action.type()==3);
  521. //速度限制
  522. stLimit adjust_x={ action.adjustvelocitylimit().min(),action.adjustvelocitylimit().max() };
  523. stLimit adjust_h={ action.adjusthorizonlimit().min(),action.adjusthorizonlimit().max() };
  524. stLimit adjust_angular={ action.nodeangularlimit().min(),action.nodeangularlimit().max() };
  525. stLimit mpc_velocity={ action.nodevelocitylimit().min(),action.nodevelocitylimit().max() };
  526. /*原地调整起点
  527. NavMessage::PathNode first=action.pathnodes(0);
  528. //目标,精度
  529. double first_yaw=timedPose_.Get().theta();
  530. if(1<action.pathnodes_size()){
  531. NavMessage::PathNode next=action.pathnodes(1);
  532. first_yaw=Pose2d::vector2yaw(next.pose().x()-first.pose().x(),next.pose().y()-first.pose().y());
  533. }
  534. Pose2d first_target(first.pose().x(),first.pose().y(),first_yaw);
  535. Pose2d first_accuracy(first.accuracy().x(),first.accuracy().y(),first.accuracy().theta());
  536. execute_adjust_action(first_target,first_accuracy,adjust_x,adjust_h,adjust_angular,anyDirect);
  537. Pose2d last_node=first_target;*/
  538. for(int i=0;i< action.pathnodes_size();++i) {
  539. NavMessage::PathNode node = action.pathnodes(i);
  540. /// 巡线到目标点,判断巡线方向
  541. Pose2d target(node.pose().x(), node.pose().y(), node.pose().theta());
  542. Pose2d accuracy(node.accuracy().x(), node.accuracy().y(), node.accuracy().theta());
  543. while (cancel_ == false) {
  544. if (IsArrived(timedPose_.Get(), timedV_.Get(), timedA_.Get(), target, Pose2d::abs(accuracy))) {
  545. break;
  546. }
  547. if (RotateReferToTarget(target, adjust_angular, anyDirect) == false) {
  548. std::cout << " Rotate refer to target failed,target:" << target <<
  549. " anyDirect:" << anyDirect << std::endl;
  550. return false;
  551. }
  552. MpcResult ret = execute_along_action(timedPose_.Get(), target, accuracy, mpc_velocity, anyDirect);
  553. if (ret == eMpcSuccess) {
  554. std::cout << " MPC to target " << target << " completed" << std::endl;
  555. break;
  556. } else if (ret == eImpossibleToTarget) {
  557. std::cout << " MPC to target " << target << " impossible to target,retry" << std::endl;
  558. } else {
  559. return false;
  560. }
  561. }
  562. if (cancel_) {
  563. return false;
  564. }
  565. }
  566. return true;
  567. }
  568. printf("execute PathNode failed ,action type is not 3/4 :%d\n",action.type());
  569. return false;
  570. }
  571. bool Navigation::execute_vehicle_mode(NavMessage::NewAction action){
  572. if(action.type()==5 ) //最优动作导航 or 导航中保证朝向严格一致
  573. {
  574. if (!action.has_nodevelocitylimit() || !action.has_nodeangularlimit() ||
  575. !action.has_adjustvelocitylimit() || !action.has_adjusthorizonlimit()
  576. || action.pathnodes_size() == 0) {
  577. std::cout << "execute pathNodes failed ,Action invalid:" << action.DebugString() << std::endl;
  578. return false;
  579. //原地调整起点
  580. NavMessage::PathNode first=action.pathnodes(0);
  581. //速度限制
  582. stLimit adjust_x={ action.adjustvelocitylimit().min(),action.adjustvelocitylimit().max() };
  583. stLimit adjust_h={ action.adjusthorizonlimit().min(),action.adjusthorizonlimit().max() };
  584. stLimit adjust_angular={ action.nodeangularlimit().min(),action.nodeangularlimit().max() };
  585. stLimit mpc_velocity={ action.nodevelocitylimit().min(),action.nodevelocitylimit().max() };
  586. //目标,精度
  587. double first_yaw=timedPose_.Get().theta();
  588. if(1<action.pathnodes_size()){
  589. NavMessage::PathNode next=action.pathnodes(1);
  590. first_yaw=Pose2d::vector2yaw(next.pose().x()-first.pose().x(),next.pose().y()-first.pose().y());
  591. }
  592. Pose2d first_target(first.pose().x(),first.pose().y(),first_yaw);
  593. Pose2d first_accuracy(first.accuracy().x(),first.accuracy().y(),first.accuracy().theta());
  594. //execute_adjust_action(first_target,first_accuracy,adjust_x,adjust_h,adjust_angular,anyDirect);
  595. return false;
  596. }
  597. }else{
  598. return false;
  599. }
  600. }
  601. bool Navigation::execute_InOut_space(NavMessage::NewAction action) {
  602. if (action.type() != 1 && action.type() != 2) {
  603. printf(" Inout_space failed : msg action type must ==1\n ");
  604. return false;
  605. }
  606. if (!action.has_inoutvlimit() || !action.has_spacenode() ||
  607. !action.has_streetnode()) {
  608. std::cout << "execute enter_space failed ,Action miss some infos:" << action.DebugString() << std::endl;
  609. return false;
  610. }
  611. if (PoseTimeout() == true) {
  612. printf(" inout_space failed type:%d : current pose is timeout\n", action.type());
  613. return false;
  614. }
  615. Pose2d begin, target, begin_accuracy, target_accuracy;
  616. //入库,起点为streetNode
  617. begin = Pose2d(action.streetnode().pose().x(), action.streetnode().pose().y(), action.streetnode().pose().theta());
  618. begin_accuracy = Pose2d(action.streetnode().accuracy().x(),
  619. action.streetnode().accuracy().y(),
  620. action.streetnode().accuracy().theta());
  621. target = Pose2d(action.spacenode().pose().x(), action.spacenode().pose().y(), action.spacenode().pose().theta());
  622. //目标点精度
  623. target_accuracy = Pose2d(action.spacenode().accuracy().x()*2,
  624. action.spacenode().accuracy().y()*2,
  625. action.spacenode().accuracy().theta()*2);
  626. double yaw = Pose2d::vector2yaw(target.x() - begin.x(), target.y() - begin.y());
  627. if (action.type() == 2) { //出库起点终点对调
  628. Pose2d mid = target;
  629. Pose2d mid_accuracy = target_accuracy;
  630. target = begin;
  631. target_accuracy = begin_accuracy;
  632. begin = mid;
  633. begin_accuracy = mid_accuracy;
  634. yaw = Pose2d::vector2yaw(begin.x() - target.x(), begin.y() - target.y());
  635. }
  636. //给起点赋予朝向,保证agv以正对车位的方向行进
  637. begin.mutable_theta() = yaw;
  638. //严格调整到起点
  639. stLimit adjust_x = {0.05, 0.2};
  640. stLimit adjust_h = {0.05, 0.2};
  641. stLimit adjust_angular = {2 * M_PI / 180.0, 20 * M_PI / 180.0};
  642. stLimit mpc_velocity = {0.05, 0.3};
  643. //判断当前点与起点的距离
  644. Pose2d distance(1, 1, M_PI * 2);
  645. if (action.type() == 2) { //出库要求起点距离当前点非常近
  646. distance = Pose2d(1, 0.1, 3 * M_PI);
  647. adjust_x = {0.03, 0.1};
  648. adjust_h = {0.03, 0.1};
  649. adjust_angular = {2 * M_PI / 180.0, 5 * M_PI / 180.0};
  650. }
  651. Pose2d relativeDiff=Pose2d::relativePose(begin,timedPose_.Get());
  652. if (!(Pose2d::abs(relativeDiff) < distance)) {
  653. printf(" Inout space failed type:%d: current pose too far from begin node\n", action.type());
  654. std::cout << " begin:" << begin << " current:" << timedPose_.Get()<<" relative:"<<relativeDiff << std::endl;
  655. return false;
  656. }
  657. if (action.type() == 1) //1,进库,先调整到库位前方(起点)
  658. if (execute_adjust_action(begin, begin_accuracy, adjust_x, adjust_h, adjust_angular, true) == false)
  659. return false;
  660. if (execute_along_action(begin, target, target_accuracy, mpc_velocity, true) == false)
  661. return false;
  662. return true;
  663. }
  664. bool Navigation::mpc_once(Trajectory traj,stLimit limit_v,std::vector<double>& out,bool directY) {
  665. if (PoseTimeout() == true) {
  666. printf(" MPC once Error:Pose is timeout \n");
  667. return false;
  668. }
  669. if(timedV_.timeout() == true || timedA_.timeout() == true){
  670. printf(" MPC once Error:V/A is timeout \n");
  671. return false;
  672. }
  673. if (traj.size() == 0) {
  674. printf("traj size ==0\n");
  675. return false;
  676. }
  677. Pose2d pose = timedPose_.Get();
  678. double velocity = timedV_.Get(); //从plc获取状态
  679. double angular = timedA_.Get();
  680. Eigen::VectorXd statu = Eigen::VectorXd::Zero(5);//agv状态
  681. statu[0] = pose.x();
  682. statu[1] = pose.y();
  683. statu[2] = pose.theta();
  684. statu[3] = velocity;
  685. statu[4] = angular;
  686. Trajectory optimize_trajectory;
  687. Trajectory selected_trajectory;
  688. NavParameter::MPC_parameter mpc_parameter=parameter_.x_mpc_parameter();
  689. double obs_w=0.85;
  690. double obs_h=1.45;
  691. if (directY == true) {
  692. //将车身朝向旋转90°,车身朝向在(-pi,pi]
  693. statu[2] += M_PI / 2;
  694. if (statu[2] > M_PI)
  695. statu[2] -= 2 * M_PI;
  696. mpc_parameter=parameter_.y_mpc_parameter();
  697. obs_w=1.45;
  698. obs_h=0.85;
  699. }
  700. Pose2d brother = timedBrotherPose_.Get();
  701. Pose2d relative = Pose2d::relativePose(brother, pose);
  702. if(directY)
  703. relative = Pose2d::relativePose(brother.rotate(brother.x(),brother.y(),M_PI/2), pose.rotate(pose.x(),pose.y(),M_PI/2));//计算另一节在当前小车坐标系下的坐标
  704. //std::cout<<"pose:"<<pose<<", brother:"<<brother<<", relative:"<<relative<<std::endl;
  705. if (move_mode_ == Monitor_emqx::ActionMode::eMain)
  706. relative = Pose2d(-1e8, -1e8, 0);
  707. MpcError ret = failed;
  708. LoadedMPC MPC(relative, obs_w,obs_h,limit_v.min, limit_v.max);
  709. LoadedMPC::MPC_parameter parameter={mpc_parameter.shortest_radius(),mpc_parameter.dt(),
  710. mpc_parameter.acc_velocity(),mpc_parameter.acc_angular()};
  711. //printf(" r:%f dt:%f acc:%f acc_a:%f\n",mpc_parameter.shortest_radius(),
  712. // mpc_parameter.dt(),mpc_parameter.acc_velocity(),mpc_parameter.acc_angular());
  713. ret = MPC.solve(traj, traj[traj.size() - 1], statu,parameter,
  714. out, selected_trajectory, optimize_trajectory);
  715. //std::cout<<" traj size %d %d -------- "<<selected_trajectory.size()<<","<<optimize_trajectory.size()<<std::endl;
  716. if(ret==no_solution) {
  717. printf(" mpc solve no solution set v/w = 0\n");
  718. out.clear();
  719. out.push_back(0);
  720. out.push_back(0);
  721. }
  722. predict_traj_.reset(optimize_trajectory, 1);
  723. selected_traj_.reset(selected_trajectory, 1);
  724. return ret==success || ret==no_solution;
  725. }
  726. bool Navigation::IsArrived(const Pose2d& cur,double velocity,double angular,
  727. const Pose2d& target,const Pose2d& diff,int direct)
  728. {
  729. //std::cout<<cur<<","<<target<<","<<nearest_yaw<<",v"<<velocity<<"a:"<<angular<<"diff:"<<diff<<std::endl;
  730. Pose2d distance=Pose2d::relativePose(target,cur);
  731. Pose2d absDiff=Pose2d::abs(distance);
  732. //std::cout<<" arrive distanc:"<<distance<<",direct:"<<direct<<std::endl;
  733. if(direct==1){ //纵向MPC
  734. if(absDiff.x()<diff.x() && absDiff.y()<diff.y())
  735. {
  736. float diffYaw=absDiff.theta(); //[0-pi)
  737. float diffYaw2=absDiff.theta()-M_PI;
  738. bool yawArrived=( fabs(diffYaw)<diff.theta() || fabs(diffYaw2)<diff.theta() );
  739. if(yawArrived && fabs(velocity) < 0.06 && fabs(angular) < 10 * M_PI / 180.0)
  740. return true;
  741. }
  742. }else if(direct==2){ //横向MPC
  743. if(absDiff.x()<diff.x() && absDiff.y()<diff.y())
  744. {
  745. float diffYaw=absDiff.theta(); //[0-pi)
  746. float diffYaw1=absDiff.theta()-M_PI/2;
  747. float diffYaw2=absDiff.theta()-M_PI;
  748. float diffYaw3=absDiff.theta()-3*M_PI/2;
  749. printf(" diff 123 :%f %f %f %f\n",diffYaw,diffYaw1,diffYaw2,diffYaw3);
  750. bool yawArrived=( fabs(diffYaw)<diff.theta() || fabs(diffYaw1)<diff.theta()
  751. || fabs(diffYaw2)<diff.theta() ||fabs(diffYaw3)<diff.theta() );
  752. if(yawArrived && fabs(velocity) < 0.06 && fabs(angular) < 10 * M_PI / 180.0)
  753. return true;
  754. }
  755. }else{ //原地调整
  756. if (absDiff < diff) {
  757. if (fabs(velocity) < 0.06 && fabs(angular) < 10 * M_PI / 180.0)
  758. return true;
  759. }
  760. }
  761. //std::cout<<"distance:"<<distance<<" diff:"<<diff<<" v:"<<velocity<<" a:"<<angular<<std::endl;
  762. return false;
  763. }
  764. bool Navigation::IsArrived(const Pose2d& cur,double velocity,double angular,
  765. const Pose2d& target,const Pose2d& diff)
  766. {
  767. //std::cout<<cur<<","<<target<<","<<nearest_yaw<<",v"<<velocity<<"a:"<<angular<<"diff:"<<diff<<std::endl;
  768. Pose2d distance=Pose2d::relativePose(target,cur);
  769. Pose2d absDiff=Pose2d::abs(distance);
  770. //std::cout<<" arrive distanc:"<<distance<<",direct:"<<direct<<std::endl;
  771. if(absDiff.x()<diff.x() && absDiff.y()<diff.y())
  772. {
  773. if(fabs(velocity) < 0.06 && fabs(angular) < 5 * M_PI / 180.0)
  774. return true;
  775. }
  776. //std::cout<<"distance:"<<distance<<" diff:"<<diff<<" v:"<<velocity<<" a:"<<angular<<std::endl;
  777. return false;
  778. }
  779. void Navigation::SendMoveCmd(Monitor_emqx::ActionMode mode,Monitor_emqx::ActionType type,
  780. double v,double angular){
  781. if(monitor_) {
  782. monitor_->set_speed(mode, type, v, angular);
  783. }
  784. }
  785. bool Navigation::clamp_close()
  786. {
  787. if(monitor_) {
  788. printf("Clamp closing...\n");
  789. monitor_->clamp_close(move_mode_);
  790. actionType_=eClampClose;
  791. while (cancel_ == false) {
  792. if (timed_clamp_.timeout()) {
  793. printf("timed clamp is timeout\n");
  794. return false;
  795. }
  796. if (timed_clamp_.Get() == eClosed)
  797. return true;
  798. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  799. monitor_->clamp_close(move_mode_);
  800. actionType_=eClampClose;
  801. }
  802. return false;
  803. }
  804. return false;
  805. }
  806. bool Navigation::clamp_open() {
  807. if(monitor_) {
  808. printf("Clamp openning...\n");
  809. monitor_->clamp_open(move_mode_);
  810. actionType_=eClampOpen;
  811. while(cancel_==false)
  812. {
  813. if(timed_clamp_.timeout())
  814. {
  815. printf("timed clamp is timeout\n");
  816. return false;
  817. }
  818. if(timed_clamp_.Get()==eOpened)
  819. return true;
  820. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  821. monitor_->clamp_open(move_mode_);
  822. actionType_=eClampOpen;
  823. }
  824. return false;
  825. }
  826. return false;
  827. }
  828. Navigation::MpcResult Navigation::execute_along_action(const Pose2d& begin,const Pose2d& target,const Pose2d& target_diff,
  829. stLimit limit_v,bool autoDirect) {
  830. if (inited_ == false) {
  831. printf(" navigation has not inited\n");
  832. return eMpcFailed;
  833. }
  834. if (PoseTimeout()) {
  835. printf(" navigation Error:Pose is timeout \n");
  836. return eMpcFailed;
  837. }
  838. //生成轨迹
  839. Trajectory traj = Trajectory::create_line_trajectory(begin, target);
  840. if (traj.size() == 0)
  841. return eMpcSuccess;
  842. //判断 巡线方向
  843. bool directY=false;
  844. if(autoDirect){
  845. Pose2d target_relative=Pose2d::relativePose(target,timedPose_.Get());
  846. if( fabs(target_relative.y())>fabs(target_relative.x())) { //目标轨迹点在当前点Y轴上
  847. std::cout<<" MPC Y axis target_relative:"<<target_relative<<std::endl;
  848. directY = true;
  849. }else{
  850. std::cout<<" MPC X axis target_relative:"<<target_relative<<std::endl;
  851. }
  852. }
  853. printf(" exec along autoDirect:%d\n",autoDirect);
  854. while (cancel_ == false) {
  855. std::this_thread::sleep_for(std::chrono::milliseconds(50));
  856. if (pause_ == true) {
  857. //发送暂停消息
  858. continue;
  859. }
  860. if (PoseTimeout()) {
  861. printf(" navigation Error:Pose is timeout \n");
  862. return eMpcFailed;
  863. }
  864. if(timedV_.timeout() || timedA_.timeout()){
  865. printf(" navigation Error:v/a is timeout \n");
  866. return eMpcFailed;
  867. }
  868. //判断是否到达终点
  869. Pose2d target_accuracy=target_diff;
  870. if(directY)
  871. target_accuracy=Pose2d::abs(target_diff.rotate(timedPose_.Get().theta()));
  872. if (IsArrived(timedPose_.Get(), timedV_.Get(), timedA_.Get(), target, Pose2d::abs(target_accuracy),2)) {
  873. if (Stop()) {
  874. printf(" exec along completed !!!\n");
  875. return eMpcSuccess;
  876. }
  877. }
  878. //一次变速
  879. std::vector<double> out;
  880. bool ret;
  881. TimerRecord::Execute([&, this]() {
  882. ret = mpc_once(traj, limit_v, out,directY);
  883. }, "mpc_once");
  884. if (ret == false) {
  885. Stop();
  886. return eMpcFailed;
  887. }
  888. /*
  889. * AGV 在终点附近低速巡航时,设置最小速度0.05
  890. */
  891. Pose2d target_in_agv=Pose2d::relativePose(target,timedPose_.Get());
  892. if (directY) {
  893. target_in_agv=target_in_agv.rotate(M_PI / 2.0);
  894. }
  895. if(Pose2d::abs(target_in_agv)<Pose2d(0.2,2,M_PI*2)) {
  896. if (out[0] >= 0 && out[0] < limit_v.min)
  897. out[0] = limit_v.min;
  898. if (out[0] < 0 && out[0] > -limit_v.min)
  899. out[0] = -limit_v.min;
  900. }
  901. //下发速度
  902. if(directY==false)
  903. SendMoveCmd(move_mode_, Monitor_emqx::eMPC, out[0], out[1]);
  904. else
  905. SendMoveCmd(move_mode_, Monitor_emqx::eHorizontal, out[0], out[1]);
  906. actionType_=eMPC;
  907. /*
  908. * 判断车辆是否在终点附近徘徊,无法到达终点
  909. */
  910. if (mpc_possible_to_end(target, target_accuracy,directY) == false) {
  911. printf(" --------------MPC imposible to target -----------------------\n");
  912. if(fabs(timedV_.Get())>0.1 || fabs(timedA_.Get())>5*M_PI/180.0)
  913. Stop();
  914. return eImpossibleToTarget;
  915. //调整到目标点
  916. /*stLimit limitv, limitR;
  917. limitv.min = 0.05;
  918. limitv.max = 0.1;
  919. limitR.min = 2 * M_PI / 180.0;
  920. limitR.max = 10 * M_PI / 180.0;
  921. Pose2d accuracy(target_diff.x(),target_diff.y(),M_PI*2);
  922. if (execute_adjust_action(target, accuracy, limitv, limitv, limitR,false))
  923. return true;
  924. else
  925. return false;*/
  926. }
  927. //std::this_thread::sleep_for(std::chrono::milliseconds (400));
  928. }
  929. return eMpcFailed;
  930. }
  931. bool Navigation::mpc_possible_to_end(const Pose2d& target,const Pose2d& target_diff,bool directY)
  932. {
  933. if(timedPose_.timeout()==false) {
  934. Pose2d current = timedPose_.Get();
  935. Pose2d targetInPose = Pose2d::relativePose(target, current);
  936. //std::cout<<" target in pose:"<<targetInPose<<", target diff:"<<target_diff<<std::endl;
  937. if (directY) {
  938. targetInPose=targetInPose.rotate(M_PI / 2.0);
  939. }
  940. if (fabs(targetInPose.x()) < target_diff.x()) {
  941. if (fabs(targetInPose.y()) > target_diff.y())
  942. return false;
  943. else
  944. return true;
  945. } else {
  946. float y=fabs(targetInPose.y())-fabs(target_diff.y());
  947. if(y<0) y=0;
  948. Pose2d minTarget(targetInPose.x(),y,0);
  949. float cuv=compute_cuv(minTarget);
  950. if(cuv>15*M_PI/180.0)
  951. return false;
  952. return true;
  953. }
  954. }else{
  955. return false;
  956. }
  957. }
  958. void Navigation::navigatting() {
  959. if (inited_ == false) {
  960. printf(" navigation has not inited\n");
  961. return;
  962. }
  963. pause_ = false;
  964. cancel_ = false;
  965. running_ = true;
  966. actionType_ = eReady;
  967. printf(" navigation beg...\n");
  968. while (newUnfinished_cations_.empty() == false && cancel_ == false) {
  969. std::cout << "unfinished size:" << newUnfinished_cations_.size() << std::endl;
  970. NavMessage::NewAction act = newUnfinished_cations_.front();
  971. if(act.type()==1){ //入库
  972. if(!execute_InOut_space(act)){
  973. printf(" In space failed\n");
  974. break;
  975. }
  976. }
  977. else if(act.type()==2){ //出库
  978. if(!execute_InOut_space(act)){
  979. printf(" out space failed\n");
  980. break;
  981. }
  982. }else if (act.type() == 3 || act.type() == 4) { //马路导航
  983. if (!execute_nodes(act))
  984. break;
  985. }else if(act.type()==5){
  986. printf(" 汽车模型导航....\n");
  987. }else if (act.type() == 6) {//夹持
  988. if (this->clamp_close() == false) {
  989. printf("夹持failed ...\n");
  990. break;
  991. }
  992. } else if (act.type() == 7) {
  993. if (this->clamp_open() == false) {
  994. printf("打开夹持 failed...\n");
  995. break;
  996. }
  997. } else if(act.type()==8){ //切换模式
  998. SwitchMode(Monitor_emqx::ActionMode(act.changedmode()),act.wheelbase());
  999. }else{
  1000. printf(" action type invalid not handled !!\n");
  1001. break;
  1002. }
  1003. newUnfinished_cations_.pop();
  1004. }
  1005. actionType_ = eReady;
  1006. Stop();
  1007. if (cancel_ == true) {
  1008. printf(" navigation canceled\n");
  1009. while (newUnfinished_cations_.empty() == false)
  1010. newUnfinished_cations_.pop();
  1011. } else {
  1012. if (newUnfinished_cations_.empty())
  1013. printf("navigation completed!!!\n");
  1014. else {
  1015. printf(" navigation Failed\n");
  1016. while (newUnfinished_cations_.empty() == false)
  1017. newUnfinished_cations_.pop();
  1018. }
  1019. }
  1020. running_ = false;
  1021. }
  1022. void Navigation::SwitchMode(Monitor_emqx::ActionMode mode,float wheelBase){
  1023. printf("Child AGV can not Switch Mode\n");
  1024. }
  1025. float Navigation::compute_cuv(const Pose2d& target)
  1026. {
  1027. float x=fabs(target.x());
  1028. float y=fabs(target.y());
  1029. float cuv= atan(y/(x+1e-8));
  1030. printf(" ---------------------- cuv:%f\n",cuv);
  1031. return cuv;
  1032. }