main.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447
  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. bool CreateNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd);
  28. bool NavIsCompleted()
  29. {
  30. if(timed_navStatu_.timeout()==false)
  31. {
  32. if(timed_navStatu_.Get().unfinished_actions_size()>0)
  33. {
  34. return false;
  35. }
  36. return true;
  37. }
  38. return false;
  39. }
  40. bool Create_trajectoris(PathMap& map,std::vector<int> nodes_id,std::queue<Trajectory>& trajs);
  41. bool InitMap(std::string config_file);
  42. bool OnDijkstraBtn(int beg,int end,float& distance,
  43. std::vector<int>& shortestPath)
  44. {
  45. if(beg==0 || end==0)
  46. return false;
  47. next_begin_node=beg;
  48. end_node=end;
  49. bool ret= DijkstraMap.GetShortestPath(beg, end, shortestPath, distance);
  50. if(ret)
  51. {
  52. pathMutex.lock();
  53. g_shortest_path= shortestPath;
  54. std::reverse(g_shortest_path.begin(),g_shortest_path.end());
  55. g_shortest_path.push_back(end_node);
  56. pathMutex.unlock();
  57. }
  58. return ret;
  59. }
  60. void navigation_start() {
  61. if (NavIsCompleted() == false) {
  62. printf("Last nav has not completed!!\n");
  63. return;
  64. }
  65. if (next_begin_node == 0) {
  66. printf(" Last node == 0 ,not allow to start nav\n");
  67. return;
  68. }
  69. std::vector<int> t_shortestPath;
  70. float distance = -1;
  71. bool ret = DijkstraMap.GetShortestPath(next_begin_node, end_node, t_shortestPath, distance);
  72. if (ret) {
  73. pathMutex.lock();
  74. g_shortest_path = t_shortestPath;
  75. std::reverse(g_shortest_path.begin(), g_shortest_path.end());
  76. g_shortest_path.push_back(end_node);
  77. pathMutex.unlock();
  78. }
  79. auto_test_count++;
  80. //发布指令
  81. NavMessage::NavCmd cmd;
  82. if (false == CreateNavCmd(g_shortest_path, cmd))
  83. return;
  84. std::cout << " ------------------------------------new NavCmd ---------------------------" << std::endl;
  85. printf("----第 %d 次测试---- from %d ---- %d -------begin navigatting...-----\n\n",
  86. auto_test_count,next_begin_node,end_node);
  87. if (g_terminator) {
  88. MqttMsg msg;
  89. msg.fromProtoMessage(cmd);
  90. g_terminator->Publish("agv1_child/nav_cmd", msg);
  91. }
  92. }
  93. void navigation_pause()
  94. {
  95. NavMessage::NavCmd cmd;
  96. cmd.set_action(1); //暂停
  97. if(g_terminator) {
  98. MqttMsg msg;
  99. msg.fromProtoMessage(cmd);
  100. g_terminator->Publish("agv1_child/nav_cmd", msg);
  101. }
  102. }
  103. void navigation_stop()
  104. {
  105. if(NavIsCompleted()==false)
  106. {
  107. printf("Last nav has not completed!! set last node = -1\n");
  108. next_begin_node=0;
  109. }
  110. NavMessage::NavCmd cmd;
  111. cmd.set_action(3); //取消导航
  112. if(g_terminator) {
  113. MqttMsg msg;
  114. msg.fromProtoMessage(cmd);
  115. g_terminator->Publish("agv1_child/nav_cmd", msg);
  116. }
  117. }
  118. void navigation_autoTest()
  119. {
  120. g_auto_test=true;
  121. }
  122. void pangolinSpinOnce(PangolinViewer* viewer) {
  123. ///导航结束,修改起点为上一任务终点,重置终点为0
  124. if(last_nav_statu_completed==false) {
  125. if (NavIsCompleted() == true) {
  126. if (end_node != 0) {
  127. next_begin_node = end_node;
  128. //随机终点
  129. int randid=0; //[1-8]
  130. while(randid==0 || randid==next_begin_node) {
  131. randid = rand() % 7 + 1;
  132. usleep(1000*1000);
  133. }
  134. printf(" nav completed ...... reset beg:%d rand end:%d\n",next_begin_node,randid);
  135. end_node = randid;
  136. float distance;
  137. std::vector<int> shortestPath;
  138. if(OnDijkstraBtn(next_begin_node,end_node,distance,shortestPath))
  139. viewer->ResetPathInfo(next_begin_node, end_node,distance);
  140. last_nav_statu_completed=true;
  141. if(g_auto_test)
  142. navigation_start();
  143. }
  144. }
  145. }
  146. if (timed_AgvStatu_.timeout() == false) {
  147. NavMessage::AGVStatu statu = timed_AgvStatu_.Get();
  148. Pose2d pose2d(statu.x(), statu.y(), statu.theta());
  149. Eigen::Matrix3d rotation_matrix3;
  150. rotation_matrix3 = Eigen::AngleAxisd(pose2d.theta(), Eigen::Vector3d::UnitZ()) *
  151. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY()) *
  152. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX());
  153. Eigen::Matrix4d pose;
  154. pose.topLeftCorner(3, 3) = rotation_matrix3;
  155. pose.topRightCorner(3, 1) = Eigen::Vector3d(pose2d.x(), pose2d.y(), 0);
  156. viewer->ShowRealtimeStatu(pose, statu.v(), statu.vth());
  157. }
  158. //显示另一节agv状态
  159. if (timed_AgvBrotherStatu_.timeout() == false) {
  160. NavMessage::AGVStatu statu = timed_AgvBrotherStatu_.Get();
  161. Pose2d pose2d(statu.x(), statu.y(), statu.theta());
  162. Eigen::Matrix3d rotation_matrix3;
  163. rotation_matrix3 = Eigen::AngleAxisd(pose2d.theta(), Eigen::Vector3d::UnitZ()) *
  164. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY()) *
  165. Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX());
  166. Eigen::Matrix4d pose;
  167. pose.topLeftCorner(3, 3) = rotation_matrix3;
  168. pose.topRightCorner(3, 1) = Eigen::Vector3d(pose2d.x(), pose2d.y(), 0);
  169. viewer->ShowBrotherStatu(pose, statu.v(), statu.vth());
  170. }
  171. //绘制导航实时状态
  172. if (timed_navStatu_.timeout() == false) {
  173. NavMessage::NavStatu statu = timed_navStatu_.Get();
  174. Trajectory select_traj;
  175. Trajectory predict_traj;
  176. for (int i = 0; i < statu.selected_traj().poses_size(); ++i) {
  177. select_traj.push_point(Pose2d(statu.selected_traj().poses(i).x(),
  178. statu.selected_traj().poses(i).y(),
  179. statu.selected_traj().poses(i).theta()));
  180. }
  181. for (int i = 0; i < statu.predict_traj().poses_size(); ++i) {
  182. predict_traj.push_point(Pose2d(statu.predict_traj().poses(i).x(),
  183. statu.predict_traj().poses(i).y(),
  184. statu.predict_traj().poses(i).theta()));
  185. }
  186. viewer->DrawTrajectory(select_traj, 1, 0, 0, 12);
  187. viewer->DrawTrajectory(predict_traj, 0, 1, 1, 15);
  188. }
  189. //绘制dijkstra地图及最短路径
  190. viewer->DrawDijkastraMap(DijkstraMap, g_shortest_path);
  191. }
  192. void AgvStatuArrived(const MqttMsg& msg,void* context)
  193. {
  194. NavMessage::AGVStatu statu;
  195. if(msg.toProtoMessage(statu))
  196. timed_AgvStatu_.reset(statu,0.5);
  197. }
  198. void AgvBrotherStatuArrived(const MqttMsg& msg,void* context)
  199. {
  200. NavMessage::AGVStatu statu;
  201. if(msg.toProtoMessage(statu))
  202. timed_AgvBrotherStatu_.reset(statu,0.5);
  203. }
  204. void NavStatuArrived(const MqttMsg& msg,void* context)
  205. {
  206. NavMessage::NavStatu statu;
  207. if(msg.toProtoMessage(statu))
  208. timed_navStatu_.reset(statu,1.0);
  209. if(last_nav_statu_completed==true)
  210. {
  211. if(NavIsCompleted()==false)
  212. last_nav_statu_completed=false;
  213. }
  214. }
  215. int main(int argc, char** argv)
  216. {
  217. srand((unsigned int)time(nullptr));
  218. if(argc<2)
  219. {
  220. printf(" argc must >2 exe mapfile\n");
  221. return -1;
  222. }
  223. std::string config_file=argv[1];
  224. if(InitMap(config_file)==false)
  225. return -1;
  226. //"agv1/nav_statu"
  227. g_terminator=new Terminator_emqx("UI_nav-child");
  228. if(g_terminator->Connect("192.168.0.70",1883)==false)
  229. {
  230. printf(" AGV emqx connect failed\n");
  231. return -1;
  232. }
  233. g_terminator->AddCallback("agv1_child/nav_statu",NavStatuArrived, nullptr);
  234. g_terminator->AddCallback("agv1_child/agv_statu",AgvStatuArrived, nullptr);
  235. g_terminator->AddCallback("agv1/agv_statu",AgvBrotherStatuArrived, nullptr);
  236. PangolinViewer* viewer=PangolinViewer::CreateViewer();
  237. viewer->SetCallbacks(pangolinSpinOnce,OnDijkstraBtn);
  238. viewer->SetNavigationCallbacks(navigation_start,navigation_pause,navigation_stop);
  239. viewer->SetAutoTestNavCallback(navigation_autoTest);
  240. viewer->Join();
  241. TimerRecord::PrintAll();
  242. delete viewer;
  243. delete g_terminator;
  244. return 0;
  245. }
  246. bool InitMap(std::string config_file)
  247. {
  248. MapMessage::Map proto_map;
  249. if(proto_tool::read_proto_param(config_file,proto_map)==false)
  250. {
  251. printf(" read map proto failed\n");
  252. return false;
  253. }
  254. std::map<int,int> exist_id;
  255. for(int i=0;i<proto_map.nodes_size();++i)
  256. {
  257. MapMessage::Node node=proto_map.nodes(i);
  258. if(exist_id.find(node.id())!=exist_id.end())
  259. {
  260. printf("Can not add vertex, Node Id :%d exist\n",node.id());
  261. return false;
  262. }
  263. DijkstraMap.AddVertex(node.id(),node.x(),node.y());
  264. exist_id[node.id()]=0;
  265. }
  266. for(int i=0;i<proto_map.edges_size();++i)
  267. {
  268. MapMessage::Edge edge=proto_map.edges(i);
  269. if(exist_id.find(edge.id1())!=exist_id.end() && exist_id.find(edge.id2())!=exist_id.end())
  270. {
  271. if(false==DijkstraMap.AddEdge(edge.id1(),edge.id2(),edge.directed()))
  272. return false;
  273. }
  274. else
  275. {
  276. printf(" Cant add edge id1 or id2 (%d %d) is not exist\n",edge.id1(),edge.id2());
  277. return false;
  278. }
  279. }
  280. return true;
  281. }
  282. bool Create_trajectoris(PathMap& map,std::vector<int> nodes_id,std::queue<Trajectory>& trajs)
  283. {
  284. if(nodes_id.size()<2)
  285. return false;
  286. for(int i=0;i<nodes_id.size()-1;++i)
  287. {
  288. float x1,y1,x2,y2;
  289. map.GetVertexPos(nodes_id[i],x1,y1);
  290. map.GetVertexPos(nodes_id[i+1],x2,y2);
  291. Pose2d start(x1,y1,0);
  292. Pose2d end(x2,y2,0);
  293. Trajectory traj=Trajectory::create_line_trajectory(start,end,0.05);
  294. if(traj.size()>1)
  295. trajs.push(traj);
  296. else
  297. return false;
  298. }
  299. return true;
  300. }
  301. bool CreateNavCmd(std::vector<int> nodes,NavMessage::NavCmd& cmd)
  302. {
  303. if(nodes.size()==0)
  304. return false;
  305. cmd.set_action(0); //开始新导航
  306. char key[255]={0};
  307. static int N=1111;
  308. sprintf(key,"abcd-efg-%d",N++);
  309. cmd.set_key(key);
  310. NavMessage::Pose2d headdiff,enddiff;
  311. headdiff.set_x(0.1);
  312. headdiff.set_y(0.1);
  313. headdiff.set_theta(1.0*M_PI/180.0);
  314. enddiff.set_x(0.03);
  315. enddiff.set_y(0.05);
  316. enddiff.set_theta(1.0*M_PI/180.0);
  317. //调整到起点,朝向与当前朝向一致
  318. if(timed_AgvStatu_.timeout())
  319. {
  320. printf(" agv statu is timeout can not get current direction\n");
  321. return false;
  322. }
  323. float current_theta=timed_AgvStatu_.Get().theta();
  324. float x,y;
  325. DijkstraMap.GetVertexPos(nodes[0],x,y);
  326. NavMessage::SpeedLimit v_limit,angular_limit,horize_limit;
  327. v_limit.set_min(0.1);
  328. v_limit.set_max(0.2);
  329. horize_limit.set_min(0.05);
  330. horize_limit.set_max(0.2);
  331. angular_limit.set_min(1);
  332. angular_limit.set_max(30);
  333. NavMessage::SpeedLimit mpc_x_limit,mpc_angular_limit;
  334. mpc_x_limit.set_min(0.05);
  335. mpc_x_limit.set_max(1.0);
  336. mpc_angular_limit.set_min(0*M_PI/180.0);
  337. mpc_angular_limit.set_max(3*M_PI/180.0);
  338. NavMessage::Action act_head;
  339. act_head.set_type(1);
  340. act_head.mutable_target()->set_x(x);
  341. act_head.mutable_target()->set_y(y);
  342. act_head.mutable_target()->set_theta(current_theta);
  343. act_head.mutable_target_diff()->CopyFrom(headdiff);
  344. act_head.mutable_velocity_limit()->CopyFrom(v_limit);
  345. act_head.mutable_horize_limit()->CopyFrom(horize_limit);
  346. act_head.mutable_angular_limit()->CopyFrom(angular_limit);
  347. cmd.add_actions()->CopyFrom(act_head);
  348. Pose2d begin;
  349. for(int i=1;i<nodes.size();++i)
  350. {
  351. //调整到上一点位姿,朝向当前点
  352. float lx,ly;
  353. DijkstraMap.GetVertexPos(nodes[i-1],lx,ly);
  354. DijkstraMap.GetVertexPos(nodes[i],x,y);
  355. float theta=Trajectory::gen_axis_angle(Pose2d(lx,ly,0),Pose2d(x,y,0));
  356. begin=Pose2d(lx,ly,theta);
  357. NavMessage::Action act_adjust;
  358. act_adjust.set_type(1);
  359. act_adjust.mutable_target()->set_x(lx);
  360. act_adjust.mutable_target()->set_y(ly);
  361. act_adjust.mutable_target()->set_theta(theta);
  362. act_adjust.mutable_target_diff()->CopyFrom(headdiff);
  363. act_adjust.mutable_velocity_limit()->CopyFrom(v_limit);
  364. act_adjust.mutable_horize_limit()->CopyFrom(horize_limit);
  365. act_adjust.mutable_angular_limit()->CopyFrom(angular_limit);
  366. cmd.add_actions()->CopyFrom(act_adjust);
  367. //MPC 控制
  368. NavMessage::Action act_along;
  369. act_along.set_type(2);
  370. act_along.mutable_begin()->set_x(begin.x());
  371. act_along.mutable_begin()->set_y(begin.y());
  372. act_along.mutable_begin()->set_theta(begin.theta());
  373. act_along.mutable_target()->set_x(x);
  374. act_along.mutable_target()->set_y(y);
  375. act_along.mutable_target()->set_theta(theta);
  376. if(i==nodes.size()-1) //最后一个节点
  377. act_along.mutable_target_diff()->CopyFrom(enddiff);
  378. else
  379. act_along.mutable_target_diff()->CopyFrom(headdiff);
  380. act_along.mutable_velocity_limit()->CopyFrom(mpc_x_limit);
  381. act_along.mutable_angular_limit()->CopyFrom(mpc_angular_limit);
  382. cmd.add_actions()->CopyFrom(act_along);
  383. }
  384. return true;
  385. }