main.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581
  1. #include <csignal>
  2. #include "pangolinViewer.h"
  3. #include "dijkstra/dijkstra.h"
  4. #include "define/timedlockdata.hpp"
  5. #include "define/TimerRecord.h"
  6. #include <glog/logging.h>
  7. #include "dijkstra/trajectory.h"
  8. #include "emqx/terminator_emqx.h"
  9. #include "tool/pathcreator.h"
  10. #include "tool/proto_tool.h"
  11. #include <queue>
  12. #include "map.pb.h"
  13. Terminator_emqx* g_terminator= nullptr;
  14. //路径相关
  15. std::mutex pathMutex;
  16. std::vector<int> g_shortest_path;
  17. PathMap DijkstraMap;
  18. bool g_auto_test=false;
  19. int auto_test_count=0;
  20. int next_begin_node=0;
  21. int end_node=0;
  22. bool last_nav_statu_completed=true;
  23. //控制相关
  24. TimedLockData<NavMessage::NavStatu> timed_navStatu_;
  25. TimedLockData<NavMessage::AGVStatu> timed_AgvStatu_;
  26. TimedLockData<NavMessage::AGVStatu> timed_AgvBrotherStatu_;
  27. //创建单车由指定点进入车位导航指令
  28. bool CreateIntoSpaceNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd);
  29. //创建单车出车位去指定点导航指令
  30. bool CreateOutSpaceNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd);
  31. //创建单车出车位去指定点导航指令
  32. bool CreateTestNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd);
  33. bool NavIsCompleted()
  34. {
  35. if(timed_navStatu_.timeout()==false)
  36. {
  37. if(timed_navStatu_.Get().unfinished_actions_size()>0)
  38. {
  39. return false;
  40. }
  41. return true;
  42. }
  43. return false;
  44. }
  45. bool Create_trajectoris(PathMap& map,std::vector<int> nodes_id,std::queue<Trajectory>& trajs);
  46. bool InitMap(std::string config_file);
  47. bool OnDijkstraBtn(int beg,int end,float& distance,
  48. std::vector<int>& shortestPath)
  49. {
  50. if(beg==0 || end==0)
  51. return false;
  52. next_begin_node=beg;
  53. end_node=end;
  54. bool ret= DijkstraMap.GetShortestPath(beg, end, shortestPath, distance);
  55. if(ret)
  56. {
  57. pathMutex.lock();
  58. g_shortest_path= shortestPath;
  59. std::reverse(g_shortest_path.begin(),g_shortest_path.end());
  60. g_shortest_path.push_back(end_node);
  61. pathMutex.unlock();
  62. }
  63. return ret;
  64. }
  65. void navigation_start() {
  66. if (NavIsCompleted() == false) {
  67. printf("Last nav has not completed!!\n");
  68. return;
  69. }
  70. if (next_begin_node == 0) {
  71. printf(" Last node == 0 ,not allow to start nav\n");
  72. return;
  73. }
  74. std::vector<int> t_shortestPath;
  75. float distance = -1;
  76. bool ret = DijkstraMap.GetShortestPath(next_begin_node, end_node, t_shortestPath, distance);
  77. if (ret) {
  78. pathMutex.lock();
  79. g_shortest_path = t_shortestPath;
  80. std::reverse(g_shortest_path.begin(), g_shortest_path.end());
  81. g_shortest_path.push_back(end_node);
  82. pathMutex.unlock();
  83. }
  84. auto_test_count++;
  85. //发布指令
  86. NavMessage::NavCmd cmd;
  87. if (false == CreateIntoSpaceNavCmd(g_shortest_path, cmd))
  88. return;
  89. std::cout << " ------------------------------------new NavCmd ---------------------------" << std::endl;
  90. printf("----第 %d 次测试---- from %d ---- %d -------begin navigatting...-----\n\n",
  91. auto_test_count,next_begin_node,end_node);
  92. if (g_terminator) {
  93. MqttMsg msg;
  94. msg.fromProtoMessage(cmd);
  95. g_terminator->Publish("agv1_child/nav_cmd", msg);
  96. }
  97. }
  98. void navigation_pause()
  99. {
  100. NavMessage::NavCmd cmd;
  101. cmd.set_action(1); //暂停
  102. if(g_terminator) {
  103. MqttMsg msg;
  104. msg.fromProtoMessage(cmd);
  105. g_terminator->Publish("agv1_child/nav_cmd", msg);
  106. }
  107. }
  108. void navigation_stop()
  109. {
  110. g_auto_test=false;
  111. if(NavIsCompleted()==false)
  112. {
  113. printf("Last nav has not completed!! set last node = -1\n");
  114. next_begin_node=0;
  115. }
  116. NavMessage::NavCmd cmd;
  117. cmd.set_action(3); //取消导航
  118. if(g_terminator) {
  119. MqttMsg msg;
  120. msg.fromProtoMessage(cmd);
  121. g_terminator->Publish("agv1_child/nav_cmd", msg);
  122. }
  123. }
  124. void navigation_autoTest()
  125. {
  126. g_auto_test=true;
  127. }
  128. void pangolinSpinOnce(PangolinViewer* viewer) {
  129. ///导航结束,修改起点为上一任务终点,重置终点为0
  130. if(last_nav_statu_completed==false) {
  131. if (NavIsCompleted() == true) {
  132. if (end_node != 0) {
  133. next_begin_node = end_node;
  134. //随机终点
  135. int randid=0; //[1-8]
  136. while(randid==0 || randid==next_begin_node) {
  137. randid = rand() % 8 + 1;
  138. usleep(1000*1000);
  139. }
  140. printf(" nav completed ...... reset beg:%d rand end:%d\n",next_begin_node,randid);
  141. end_node = randid;
  142. float distance;
  143. std::vector<int> shortestPath;
  144. if(OnDijkstraBtn(next_begin_node,end_node,distance,shortestPath))
  145. viewer->ResetPathInfo(next_begin_node, end_node,distance);
  146. last_nav_statu_completed=true;
  147. if(g_auto_test)
  148. navigation_start();
  149. }
  150. }
  151. }
  152. if (timed_AgvStatu_.timeout() == false) {
  153. NavMessage::AGVStatu statu = timed_AgvStatu_.Get();
  154. Pose2d pose2d(statu.x(), statu.y(), statu.theta());
  155. Eigen::Matrix3d rotation_matrix3;
  156. rotation_matrix3 = Eigen::AngleAxisd(pose2d.theta(), Eigen::Vector3d::UnitZ()) *
  157. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY()) *
  158. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX());
  159. Eigen::Matrix4d pose;
  160. pose.topLeftCorner(3, 3) = rotation_matrix3;
  161. pose.topRightCorner(3, 1) = Eigen::Vector3d(pose2d.x(), pose2d.y(), 0);
  162. viewer->ShowRealtimeStatu(pose, statu.v(), statu.vth());
  163. }
  164. //显示另一节agv状态
  165. if (timed_AgvBrotherStatu_.timeout() == false) {
  166. NavMessage::AGVStatu statu = timed_AgvBrotherStatu_.Get();
  167. Pose2d pose2d(statu.x(), statu.y(), statu.theta());
  168. Eigen::Matrix3d rotation_matrix3;
  169. rotation_matrix3 = Eigen::AngleAxisd(pose2d.theta(), Eigen::Vector3d::UnitZ()) *
  170. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY()) *
  171. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX());
  172. Eigen::Matrix4d pose;
  173. pose.topLeftCorner(3, 3) = rotation_matrix3;
  174. pose.topRightCorner(3, 1) = Eigen::Vector3d(pose2d.x(), pose2d.y(), 0);
  175. viewer->ShowBrotherStatu(pose, statu.v(), statu.vth());
  176. }
  177. //绘制导航实时状态
  178. if (timed_navStatu_.timeout() == false) {
  179. NavMessage::NavStatu statu = timed_navStatu_.Get();
  180. Trajectory select_traj;
  181. Trajectory predict_traj;
  182. for (int i = 0; i < statu.selected_traj().poses_size(); ++i) {
  183. select_traj.push_point(Pose2d(statu.selected_traj().poses(i).x(),
  184. statu.selected_traj().poses(i).y(),
  185. statu.selected_traj().poses(i).theta()));
  186. }
  187. for (int i = 0; i < statu.predict_traj().poses_size(); ++i) {
  188. predict_traj.push_point(Pose2d(statu.predict_traj().poses(i).x(),
  189. statu.predict_traj().poses(i).y(),
  190. statu.predict_traj().poses(i).theta()));
  191. }
  192. viewer->DrawTrajectory(select_traj, 1, 0, 0, 12);
  193. viewer->DrawTrajectory(predict_traj, 0, 1, 1, 15);
  194. }
  195. //绘制dijkstra地图及最短路径
  196. viewer->DrawDijkastraMap(DijkstraMap, g_shortest_path);
  197. }
  198. void AgvStatuArrived(const MqttMsg& msg,void* context)
  199. {
  200. NavMessage::AGVStatu statu;
  201. if(msg.toProtoMessage(statu))
  202. timed_AgvStatu_.reset(statu,0.5);
  203. }
  204. void AgvBrotherStatuArrived(const MqttMsg& msg,void* context)
  205. {
  206. NavMessage::AGVStatu statu;
  207. if(msg.toProtoMessage(statu))
  208. timed_AgvBrotherStatu_.reset(statu,0.5);
  209. }
  210. void NavStatuArrived(const MqttMsg& msg,void* context)
  211. {
  212. NavMessage::NavStatu statu;
  213. if(msg.toProtoMessage(statu))
  214. timed_navStatu_.reset(statu,1.0);
  215. if(last_nav_statu_completed==true)
  216. {
  217. if(NavIsCompleted()==false)
  218. last_nav_statu_completed=false;
  219. }
  220. }
  221. int main(int argc, char** argv)
  222. {
  223. srand((unsigned int)time(nullptr));
  224. if(argc<2)
  225. {
  226. printf(" argc must >2 exe mapfile\n");
  227. return -1;
  228. }
  229. std::string config_file=argv[1];
  230. if(InitMap(config_file)==false)
  231. return -1;
  232. //"agv1/nav_statu"
  233. g_terminator=new Terminator_emqx("UI_nav-child");
  234. if(g_terminator->Connect("192.168.0.70",1883)==false)
  235. {
  236. printf(" AGV emqx connect failed\n");
  237. return -1;
  238. }
  239. g_terminator->AddCallback("agv1_child/nav_statu",NavStatuArrived, nullptr);
  240. g_terminator->AddCallback("agv1_child/agv_statu",AgvStatuArrived, nullptr);
  241. g_terminator->AddCallback("agv1/agv_statu",AgvBrotherStatuArrived, nullptr);
  242. PangolinViewer* viewer=PangolinViewer::CreateViewer();
  243. viewer->SetCallbacks(pangolinSpinOnce,OnDijkstraBtn);
  244. viewer->SetNavigationCallbacks(navigation_start,navigation_pause,navigation_stop);
  245. viewer->SetAutoTestNavCallback(navigation_autoTest);
  246. viewer->Join();
  247. TimerRecord::PrintAll();
  248. delete viewer;
  249. delete g_terminator;
  250. return 0;
  251. }
  252. bool InitMap(std::string config_file)
  253. {
  254. MapMessage::Map proto_map;
  255. if(proto_tool::read_proto_param(config_file,proto_map)==false)
  256. {
  257. printf(" read map proto failed\n");
  258. return false;
  259. }
  260. std::map<int,int> exist_id;
  261. for(int i=0;i<proto_map.nodes_size();++i)
  262. {
  263. MapMessage::Node node=proto_map.nodes(i);
  264. if(exist_id.find(node.id())!=exist_id.end())
  265. {
  266. printf("Can not add vertex, Node Id :%d exist\n",node.id());
  267. return false;
  268. }
  269. DijkstraMap.AddVertex(node.id(),node.x(),node.y());
  270. exist_id[node.id()]=0;
  271. }
  272. for(int i=0;i<proto_map.edges_size();++i)
  273. {
  274. MapMessage::Edge edge=proto_map.edges(i);
  275. if(exist_id.find(edge.id1())!=exist_id.end() && exist_id.find(edge.id2())!=exist_id.end())
  276. {
  277. if(false==DijkstraMap.AddEdge(edge.id1(),edge.id2(),edge.directed()))
  278. return false;
  279. }
  280. else
  281. {
  282. printf(" Cant add edge id1 or id2 (%d %d) is not exist\n",edge.id1(),edge.id2());
  283. return false;
  284. }
  285. }
  286. return true;
  287. }
  288. bool Create_trajectoris(PathMap& map,std::vector<int> nodes_id,std::queue<Trajectory>& trajs)
  289. {
  290. if(nodes_id.size()<2)
  291. return false;
  292. for(int i=0;i<nodes_id.size()-1;++i)
  293. {
  294. float x1,y1,x2,y2;
  295. map.GetVertexPos(nodes_id[i],x1,y1);
  296. map.GetVertexPos(nodes_id[i+1],x2,y2);
  297. Pose2d start(x1,y1,0);
  298. Pose2d end(x2,y2,0);
  299. Trajectory traj=Trajectory::create_line_trajectory(start,end,0.05);
  300. if(traj.size()>1)
  301. trajs.push(traj);
  302. else
  303. return false;
  304. }
  305. return true;
  306. }
  307. bool CreateIntoSpaceNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd)
  308. {
  309. if(nodes.size()==0)
  310. return false;
  311. cmd.set_action(0); //开始新导航
  312. char key[255]={0};
  313. static int N=1111;
  314. sprintf(key,"abcd-efg-%d",N++);
  315. cmd.set_key(key);
  316. NavMessage::Pose2d adjustdiff,node_mpcdiff,enddiff;
  317. adjustdiff.set_x(0.1);
  318. adjustdiff.set_y(0.05);
  319. adjustdiff.set_theta(0.5*M_PI/180.0);
  320. node_mpcdiff.set_x(0.1);
  321. node_mpcdiff.set_y(0.1);
  322. node_mpcdiff.set_theta(3*M_PI/180.0);
  323. enddiff.set_x(0.1);
  324. enddiff.set_y(0.1);
  325. enddiff.set_theta(5*M_PI/180.0);
  326. //调整到起点,朝向与当前朝向一致
  327. if(timed_AgvStatu_.timeout())
  328. {
  329. printf(" agv statu is timeout can not get current direction\n");
  330. return false;
  331. }
  332. float current_theta=timed_AgvStatu_.Get().theta();
  333. float x,y;
  334. DijkstraMap.GetVertexPos(nodes[0],x,y);
  335. NavMessage::SpeedLimit v_limit,angular_limit,horize_limit;
  336. v_limit.set_min(0.1);
  337. v_limit.set_max(0.2);
  338. horize_limit.set_min(0.05);
  339. horize_limit.set_max(0.2);
  340. angular_limit.set_min(1);
  341. angular_limit.set_max(25.0);
  342. NavMessage::SpeedLimit mpc_x_limit,mpc_angular_limit;
  343. mpc_x_limit.set_min(0.05);
  344. mpc_x_limit.set_max(1.5);
  345. mpc_angular_limit.set_min(0*M_PI/180.0);
  346. mpc_angular_limit.set_max(3*M_PI/180.0);
  347. NavMessage::Action act_head;
  348. act_head.set_type(1);
  349. act_head.mutable_target()->set_x(x);
  350. act_head.mutable_target()->set_y(y);
  351. act_head.mutable_target()->set_theta(current_theta);
  352. act_head.mutable_target_diff()->CopyFrom(adjustdiff);
  353. act_head.mutable_velocity_limit()->CopyFrom(v_limit);
  354. act_head.mutable_horize_limit()->CopyFrom(horize_limit);
  355. act_head.mutable_angular_limit()->CopyFrom(angular_limit);
  356. cmd.add_actions()->CopyFrom(act_head);
  357. Pose2d begin;
  358. for(int i=1;i<nodes.size();++i)
  359. {
  360. //调整到上一点位姿,朝向当前点
  361. float lx,ly;
  362. DijkstraMap.GetVertexPos(nodes[i-1],lx,ly);
  363. DijkstraMap.GetVertexPos(nodes[i],x,y);
  364. float theta=Trajectory::gen_axis_angle(Pose2d(lx,ly,0),Pose2d(x,y,0));
  365. begin=Pose2d(lx,ly,theta);
  366. NavMessage::Action act_adjust;
  367. act_adjust.set_type(1);
  368. act_adjust.mutable_target()->set_x(lx);
  369. act_adjust.mutable_target()->set_y(ly);
  370. act_adjust.mutable_target()->set_theta(theta);
  371. act_adjust.mutable_target_diff()->CopyFrom(adjustdiff);
  372. act_adjust.mutable_velocity_limit()->CopyFrom(v_limit);
  373. act_adjust.mutable_horize_limit()->CopyFrom(horize_limit);
  374. act_adjust.mutable_angular_limit()->CopyFrom(angular_limit);
  375. cmd.add_actions()->CopyFrom(act_adjust);
  376. //MPC 控制
  377. NavMessage::Action act_along;
  378. act_along.set_type(2);
  379. act_along.mutable_begin()->set_x(begin.x());
  380. act_along.mutable_begin()->set_y(begin.y());
  381. act_along.mutable_begin()->set_theta(begin.theta());
  382. act_along.mutable_target()->set_x(x);
  383. act_along.mutable_target()->set_y(y);
  384. act_along.mutable_target()->set_theta(theta);
  385. if(i==nodes.size()-1) //最后一个节点
  386. act_along.mutable_target_diff()->CopyFrom(enddiff);
  387. else
  388. act_along.mutable_target_diff()->CopyFrom(node_mpcdiff);
  389. act_along.mutable_velocity_limit()->CopyFrom(mpc_x_limit);
  390. act_along.mutable_angular_limit()->CopyFrom(mpc_angular_limit);
  391. cmd.add_actions()->CopyFrom(act_along);
  392. }
  393. return true;
  394. }
  395. bool CreateOutSpaceNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd)
  396. {
  397. if(nodes.size()==0)
  398. return false;
  399. cmd.set_action(0); //开始新导航
  400. char key[255]={0};
  401. static int N=1111;
  402. sprintf(key,"abcd-efg-%d",N++);
  403. cmd.set_key(key);
  404. NavMessage::Pose2d headdiff,enddiff;
  405. headdiff.set_x(0.1);
  406. headdiff.set_y(0.1);
  407. headdiff.set_theta(1.0*M_PI/180.0);
  408. enddiff.set_x(0.03);
  409. enddiff.set_y(0.05);
  410. enddiff.set_theta(1.0*M_PI/180.0);
  411. if(timed_AgvStatu_.timeout())
  412. {
  413. printf(" agv statu is timeout can not get current direction\n");
  414. return false;
  415. }
  416. float current_theta=timed_AgvStatu_.Get().theta();
  417. float x,y;
  418. DijkstraMap.GetVertexPos(nodes[0],x,y);
  419. NavMessage::SpeedLimit v_limit,angular_limit,horize_limit;
  420. v_limit.set_min(0.1);
  421. v_limit.set_max(0.2);
  422. horize_limit.set_min(0.05);
  423. horize_limit.set_max(0.2);
  424. angular_limit.set_min(1);
  425. angular_limit.set_max(30);
  426. NavMessage::SpeedLimit mpc_x_limit,mpc_angular_limit;
  427. mpc_x_limit.set_min(0.05);
  428. mpc_x_limit.set_max(1.0);
  429. mpc_angular_limit.set_min(0*M_PI/180.0);
  430. mpc_angular_limit.set_max(3*M_PI/180.0);
  431. NavMessage::Action act_head;
  432. act_head.set_type(1);
  433. act_head.mutable_target()->set_x(x);
  434. act_head.mutable_target()->set_y(y);
  435. act_head.mutable_target()->set_theta(current_theta);
  436. act_head.mutable_target_diff()->CopyFrom(headdiff);
  437. act_head.mutable_velocity_limit()->CopyFrom(v_limit);
  438. act_head.mutable_horize_limit()->CopyFrom(horize_limit);
  439. act_head.mutable_angular_limit()->CopyFrom(angular_limit);
  440. cmd.add_actions()->CopyFrom(act_head);
  441. Pose2d begin;
  442. for(int i=1;i<nodes.size();++i)
  443. {
  444. //调整到上一点位姿,朝向当前点
  445. float lx,ly;
  446. DijkstraMap.GetVertexPos(nodes[i-1],lx,ly);
  447. DijkstraMap.GetVertexPos(nodes[i],x,y);
  448. float theta=Trajectory::gen_axis_angle(Pose2d(lx,ly,0),Pose2d(x,y,0));
  449. //第一点倒退出车位
  450. if(i==1)
  451. theta=Trajectory::gen_axis_angle(Pose2d(x,y,0),Pose2d(lx,ly,0));
  452. begin=Pose2d(lx,ly,theta);
  453. NavMessage::Action act_adjust;
  454. act_adjust.set_type(1);
  455. act_adjust.mutable_target()->set_x(lx);
  456. act_adjust.mutable_target()->set_y(ly);
  457. act_adjust.mutable_target()->set_theta(theta);
  458. act_adjust.mutable_target_diff()->CopyFrom(headdiff);
  459. act_adjust.mutable_velocity_limit()->CopyFrom(v_limit);
  460. act_adjust.mutable_horize_limit()->CopyFrom(horize_limit);
  461. act_adjust.mutable_angular_limit()->CopyFrom(angular_limit);
  462. cmd.add_actions()->CopyFrom(act_adjust);
  463. //MPC 控制
  464. NavMessage::Action act_along;
  465. act_along.set_type(2);
  466. act_along.mutable_begin()->set_x(begin.x());
  467. act_along.mutable_begin()->set_y(begin.y());
  468. act_along.mutable_begin()->set_theta(begin.theta());
  469. act_along.mutable_target()->set_x(x);
  470. act_along.mutable_target()->set_y(y);
  471. act_along.mutable_target()->set_theta(theta);
  472. if(i==nodes.size()-1) //最后一个节点
  473. act_along.mutable_target_diff()->CopyFrom(enddiff);
  474. else
  475. act_along.mutable_target_diff()->CopyFrom(headdiff);
  476. act_along.mutable_velocity_limit()->CopyFrom(mpc_x_limit);
  477. act_along.mutable_angular_limit()->CopyFrom(mpc_angular_limit);
  478. cmd.add_actions()->CopyFrom(act_along);
  479. }
  480. return true;
  481. }
  482. bool CreateTestNavCmd(int begin,int space,int outnode,NavMessage::NavCmd& cmd)
  483. {
  484. //去车位生成路径
  485. std::vector<int> t_shortestPath;
  486. float distance = -1;
  487. bool ret = DijkstraMap.GetShortestPath(begin, space, t_shortestPath, distance);
  488. if (ret) {
  489. pathMutex.lock();
  490. g_shortest_path = t_shortestPath;
  491. std::reverse(g_shortest_path.begin(), g_shortest_path.end());
  492. g_shortest_path.push_back(end_node);
  493. pathMutex.unlock();
  494. }
  495. //生成去车位指令
  496. NavMessage::NavCmd toCmd;
  497. return false;
  498. }