RobotNavigator.cpp
Go to the documentation of this file.
1 #include <nav2d_operator/cmd.h>
2 #include <nav_msgs/GridCells.h>
3 #include <visualization_msgs/Marker.h>
4 
7 
8 #include <set>
9 #include <map>
10 
11 #define PI 3.14159265
12 
13 using namespace ros;
14 using namespace tf;
15 
17 {
18  NodeHandle robotNode;
19 
20  std::string serviceName;
21  robotNode.param("map_service", serviceName, std::string("get_map"));
22  mGetMapClient = robotNode.serviceClient<nav_msgs::GetMap>(serviceName);
23 
24  mCommandPublisher = robotNode.advertise<nav2d_operator::cmd>("cmd", 1);
25  mStopServer = robotNode.advertiseService(NAV_STOP_SERVICE, &RobotNavigator::receiveStop, this);
26  mPauseServer = robotNode.advertiseService(NAV_PAUSE_SERVICE, &RobotNavigator::receivePause, this);
27  mCurrentPlan = NULL;
28 
29  NodeHandle navigatorNode("~/");
30  mPlanPublisher = navigatorNode.advertise<nav_msgs::GridCells>("plan", 1);
31  mMarkerPublisher = navigatorNode.advertise<visualization_msgs::Marker>("markers", 1, true);
32 
33  // Get parameters
34  navigatorNode.param("map_inflation_radius", mInflationRadius, 1.0);
35  navigatorNode.param("robot_radius", mRobotRadius, 0.3);
36  navigatorNode.param("exploration_strategy", mExplorationStrategy, std::string("NearestFrontierPlanner"));
37  navigatorNode.param("navigation_goal_distance", mNavigationGoalDistance, 1.0);
38  navigatorNode.param("navigation_goal_angle", mNavigationGoalAngle, 1.0);
39  navigatorNode.param("exploration_goal_distance", mExplorationGoalDistance, 3.0);
40  navigatorNode.param("navigation_homing_distance", mNavigationHomingDistance, 3.0);
41  navigatorNode.param("min_replanning_period", mMinReplanningPeriod, 3.0);
42  navigatorNode.param("max_replanning_period", mMaxReplanningPeriod, 1.0);
43  navigatorNode.param("command_target_distance", mCommandTargetDistance, 1.0);
44  navigatorNode.param("frequency", mFrequency, 10.0);
45  mCostObstacle = 100;
46  mCostLethal = (1.0 - (mRobotRadius / mInflationRadius)) * (double)mCostObstacle;
47 
48  robotNode.param("map_frame", mMapFrame, std::string("map"));
49  robotNode.param("robot_frame", mRobotFrame, std::string("robot"));
50  robotNode.param("robot_id", mRobotID, 1);
51  robotNode.param("move_action_topic", mMoveActionTopic, std::string(NAV_MOVE_ACTION));
52  robotNode.param("explore_action_topic", mExploreActionTopic, std::string(NAV_EXPLORE_ACTION));
53  robotNode.param("getmap_action_topic", mGetMapActionTopic, std::string(NAV_GETMAP_ACTION));
54  robotNode.param("localize_action_topic", mLocalizeActionTopic, std::string(NAV_LOCALIZE_ACTION));
55 
56  // Apply tf_prefix to all used frame-id's
57  mRobotFrame = mTfListener.resolve(mRobotFrame);
58  mMapFrame = mTfListener.resolve(mMapFrame);
59 
60  try
61  {
62  mPlanLoader = new PlanLoader("nav2d_navigator", "ExplorationPlanner");
63  mExplorationPlanner = mPlanLoader->createInstance(mExplorationStrategy);
64  ROS_INFO("Successfully loaded exploration strategy [%s].", mExplorationStrategy.c_str());
65 
66  mExploreActionServer = new ExploreActionServer(mExploreActionTopic, boost::bind(&RobotNavigator::receiveExploreGoal, this, _1), false);
67  mExploreActionServer->start();
68  }
70  {
71  ROS_ERROR("Failed to load exploration plugin! Error: %s", ex.what());
72  mExploreActionServer = NULL;
73  mPlanLoader = NULL;
74  }
75 
76  // Create action servers
77  mMoveActionServer = new MoveActionServer(mMoveActionTopic, boost::bind(&RobotNavigator::receiveMoveGoal, this, _1), false);
78  mMoveActionServer->start();
79 
80  mLocalizeActionServer = new LocalizeActionServer(mLocalizeActionTopic, boost::bind(&RobotNavigator::receiveLocalizeGoal, this, _1), false);
81  mLocalizeActionServer->start();
82 
83  if(mRobotID == 1)
84  {
85  mGetMapActionServer = new GetMapActionServer(mGetMapActionTopic, boost::bind(&RobotNavigator::receiveGetMapGoal, this, _1), false);
86  mGetMapActionServer->start();
87  }else
88  {
89  mGetMapActionServer = NULL;
90  }
91 
92  mHasNewMap = false;
93  mIsStopped = false;
94  mIsPaused = false;
95  mStatus = NAV_ST_IDLE;
96  mCellInflationRadius = 0;
97 }
98 
100 {
101  delete[] mCurrentPlan;
102  delete mMoveActionServer;
103  delete mExploreActionServer;
104  delete mGetMapActionServer;
105  mExplorationPlanner.reset();
106  delete mPlanLoader;
107 }
108 
110 {
111  if(mHasNewMap) return true;
112 
113  if(!mGetMapClient.isValid())
114  {
115  ROS_ERROR("GetMap-Client is invalid!");
116  return false;
117  }
118 
119  nav_msgs::GetMap srv;
120  if(!mGetMapClient.call(srv))
121  {
122  ROS_INFO("Could not get a map.");
123  return false;
124  }
125  mCurrentMap.update(srv.response.map);
126 
127  if(mCurrentPlan) delete[] mCurrentPlan;
128  mCurrentPlan = new double[mCurrentMap.getSize()];
129 
130  if(mCellInflationRadius == 0)
131  {
132  ROS_INFO("Navigator is now initialized.");
133  mCellInflationRadius = mInflationRadius / mCurrentMap.getResolution();
134  mCellRobotRadius = mRobotRadius / mCurrentMap.getResolution();
135  mInflationTool.computeCaches(mCellInflationRadius);
136  mCurrentMap.setLethalCost(mCostLethal);
137  }
138 
139  mHasNewMap = true;
140  return true;
141 }
142 
143 bool RobotNavigator::receiveStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
144 {
145  mIsStopped = true;
146  res.success = true;
147  res.message = "Navigator received stop signal.";
148  return true;
149 }
150 
151 bool RobotNavigator::receivePause(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
152 {
153  if(mIsPaused)
154  {
155  mIsPaused = false;
156  res.success = false;
157  res.message = "Navigator continues.";
158  }else
159  {
160  mIsPaused = true;
161  nav2d_operator::cmd stopMsg;
162  stopMsg.Turn = 0;
163  stopMsg.Velocity = 0;
164  mCommandPublisher.publish(stopMsg);
165  res.success = true;
166  res.message = "Navigator pauses.";
167  }
168  return true;
169 }
170 
171 typedef std::multimap<double,unsigned int> Queue;
172 typedef std::pair<double,unsigned int> Entry;
173 
175 {
176  // Get the current map
177  if(!getMap()) // return false;
178  {
179  if(mCellInflationRadius == 0) return false;
180  ROS_WARN("Could not get a new map, trying to go with the old one...");
181  }
182 
183  // Where am I?
184  if(!setCurrentPosition()) return false;
185 
186  // Clear robot footprint in map
187  unsigned int x = 0, y = 0;
188  if(mCurrentMap.getCoordinates(x, y, mStartPoint))
189  for(int i = -mCellRobotRadius; i < (int)mCellRobotRadius; i++)
190  for(int j = -mCellRobotRadius; j < (int)mCellRobotRadius; j++)
191  mCurrentMap.setData(x+i, y+j, 0);
192 
193  mInflationTool.inflateMap(&mCurrentMap);
194  return true;
195 }
196 
198 {
199  ROS_DEBUG("Map-Value of goal point is %d, lethal threshold is %d.", mCurrentMap.getData(mGoalPoint), mCostLethal);
200 
201  unsigned int goal_x = 0, goal_y = 0;
202  if(mCurrentMap.getCoordinates(goal_x,goal_y,mGoalPoint))
203  {
204  visualization_msgs::Marker marker;
205  marker.header.frame_id = "/map";
206  marker.header.stamp = ros::Time();
207  marker.id = 0;
208  marker.type = visualization_msgs::Marker::CYLINDER;
209  marker.action = visualization_msgs::Marker::ADD;
210  marker.pose.position.x = mCurrentMap.getOriginX() + (((double)goal_x+0.5) * mCurrentMap.getResolution());
211  marker.pose.position.y = mCurrentMap.getOriginY() + (((double)goal_y+0.5) * mCurrentMap.getResolution());
212  marker.pose.position.z = 0.5;
213  marker.pose.orientation.x = 0.0;
214  marker.pose.orientation.y = 0.0;
215  marker.pose.orientation.z = 0.0;
216  marker.pose.orientation.w = 1.0;
217  marker.scale.x = mCurrentMap.getResolution() * 3.0;
218  marker.scale.y = mCurrentMap.getResolution() * 3.0;
219  marker.scale.z = 1.0;
220  marker.color.a = 1.0;
221  marker.color.r = 1.0;
222  marker.color.g = 0.0;
223  marker.color.b = 0.0;
224  mMarkerPublisher.publish(marker);
225  }else
226  {
227  ROS_ERROR("Couldn't ressolve goal point coordinates!");
228  }
229 
230  Queue queue;
231 
232  // Reset the plan
233  int mapSize = mCurrentMap.getSize();
234  for(int i = 0; i < mapSize; i++)
235  {
236  mCurrentPlan[i] = -1;
237  }
238 
239  if(mCurrentMap.isFree(mGoalPoint))
240  {
241  queue.insert(Entry(0.0, mGoalPoint));
242  mCurrentPlan[mGoalPoint] = 0;
243  }else
244  {
245  // Initialize the queue with area around the goal point
246  int reach = mCellRobotRadius + (1.0 / mCurrentMap.getResolution());
247  std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(mGoalPoint, reach);
248  for(unsigned int i = 0; i < neighbors.size(); i++)
249  {
250  queue.insert(Entry(0.0, neighbors[i]));
251  mCurrentPlan[neighbors[i]] = 0;
252  }
253  }
254 
255  Queue::iterator next;
256  double distance;
257  unsigned int x, y, index;
258  double linear = mCurrentMap.getResolution();
259  double diagonal = std::sqrt(2.0) * linear;
260 
261  // Do full search with Dijkstra-Algorithm
262  while(!queue.empty())
263  {
264  // Get the nearest cell from the queue
265  next = queue.begin();
266  distance = next->first;
267  index = next->second;
268  queue.erase(next);
269 
270  if(mCurrentPlan[index] >= 0 && mCurrentPlan[index] < distance) continue;
271 
272 // if(index == mStartPoint) break;
273 
274  // Add all adjacent cells
275  if(!mCurrentMap.getCoordinates(x, y, index)) continue;
276  std::vector<unsigned int> ind;
277  ind.push_back(index - 1);
278  ind.push_back(index + 1);
279  ind.push_back(index - mCurrentMap.getWidth());
280  ind.push_back(index + mCurrentMap.getWidth());
281  ind.push_back(index - mCurrentMap.getWidth() - 1);
282  ind.push_back(index - mCurrentMap.getWidth() + 1);
283  ind.push_back(index + mCurrentMap.getWidth() - 1);
284  ind.push_back(index + mCurrentMap.getWidth() + 1);
285 
286  for(unsigned int it = 0; it < ind.size(); it++)
287  {
288  unsigned int i = ind[it];
289  if(mCurrentMap.isFree(i))
290  {
291  double delta = (it < 4) ? linear : diagonal;
292  double newDistance = distance + delta + (10 * delta * (double)mCurrentMap.getData(i) / (double)mCostObstacle);
293  if(mCurrentPlan[i] == -1 || newDistance < mCurrentPlan[i])
294  {
295  queue.insert(Entry(newDistance, i));
296  mCurrentPlan[i] = newDistance;
297  }
298  }
299  }
300  }
301 
302  if(mCurrentPlan[mStartPoint] < 0)
303  {
304  ROS_ERROR("No way between robot and goal!");
305  return false;
306  }
307 
308  publishPlan();
309  return true;
310 }
311 
313 {
314  nav_msgs::GridCells plan_msg;
315  plan_msg.header.frame_id = mMapFrame.c_str();
316  plan_msg.header.stamp = Time::now();
317 
318  plan_msg.cell_width = mCurrentMap.getResolution();
319  plan_msg.cell_height = mCurrentMap.getResolution();
320 
321  unsigned int index = mStartPoint;
322  std::vector<std::pair<double, double> > points;
323  while(true)
324  {
325  unsigned int x = 0, y = 0;
326  if(mCurrentMap.getCoordinates(x,y,index))
327  points.push_back(std::pair<double, double>(
328  ((x+0.5) * mCurrentMap.getResolution()) + mCurrentMap.getOriginX(),
329  ((y+0.5) * mCurrentMap.getResolution()) + mCurrentMap.getOriginY()
330  ));
331 
332  if(mCurrentPlan[index] == 0) break;
333 
334  unsigned int next_index = index;
335 
336  std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(index);
337  for(unsigned int i = 0; i < neighbors.size(); i++)
338  {
339  if(mCurrentPlan[neighbors[i]] >= 0 && mCurrentPlan[neighbors[i]] < mCurrentPlan[next_index])
340  next_index = neighbors[i];
341  }
342 
343  if(index == next_index) break;
344  index = next_index;
345  }
346 
347  plan_msg.cells.resize(points.size());
348  for(unsigned int i = 0; i < points.size(); i++)
349  {
350  plan_msg.cells[i].x = points[i].first;
351  plan_msg.cells[i].y = points[i].second;
352  plan_msg.cells[i].z = 0.0;
353  }
354  mPlanPublisher.publish(plan_msg);
355 }
356 
358 {
359  // Reset the plan
360  int mapSize = mCurrentMap.getSize();
361  for(int i = 0; i < mapSize; i++)
362  {
363  mCurrentPlan[i] = -1;
364  }
365 
366  // Initialize the queue with the goal point
367  Queue queue;
368  Entry goal(0.0, mGoalPoint);
369  queue.insert(goal);
370  mCurrentPlan[mGoalPoint] = 0;
371 
372  Queue::iterator next;
373  double linear = mCurrentMap.getResolution();
374 
375  // Do full search with Dijkstra-Algorithm
376  while(!queue.empty())
377  {
378  // Get the nearest cell from the queue
379  next = queue.begin();
380  double distance = next->first;
381  unsigned int index = next->second;
382  queue.erase(next);
383 
384  if(mCurrentPlan[index] >= 0 && mCurrentPlan[index] < distance) continue;
385 
386  // Add all adjacent cells
387  std::vector<unsigned int> neighbors = mCurrentMap.getNeighbors(index);
388  for(unsigned int i = 0; i < neighbors.size(); i++)
389  {
390  if(mCurrentMap.isFree(neighbors[i]))
391  {
392  mGoalPoint = neighbors[i];
393  return true;
394  }else
395  {
396  double newDistance = distance + linear;
397  if(mCurrentPlan[neighbors[i]] == -1)
398  {
399  queue.insert(Entry(newDistance, neighbors[i]));
400  mCurrentPlan[neighbors[i]] = newDistance;
401  }
402  }
403  }
404  }
405  return false;
406 }
407 
409 {
410  nav2d_operator::cmd stopMsg;
411  stopMsg.Turn = 0;
412  stopMsg.Velocity = 0;
413  mCommandPublisher.publish(stopMsg);
414  mStatus = NAV_ST_IDLE;
415  mIsPaused = false;
416  mIsStopped = false;
417 }
418 
420 {
421  // Do nothing when paused
422  if(mIsPaused)
423  {
424  ROS_INFO_THROTTLE(1.0, "Navigator is paused and will not move now.");
425  return true;
426  }
427 
428  if(mStatus != NAV_ST_NAVIGATING && mStatus != NAV_ST_EXPLORING)
429  {
430  ROS_WARN_THROTTLE(1.0, "Navigator has status %d when generateCommand() was called!", mStatus);
431  return false;
432  }
433 
434  // Generate direction command from plan
435  unsigned int current_x = 0, current_y = 0;
436  if(!mCurrentMap.getCoordinates(current_x, current_y, mStartPoint)) // || !mCurrentMap.isFree(mStartPoint))
437  {
438  ROS_ERROR("Plan execution failed, robot not in map!");
439  return false;
440  }
441 
442  unsigned int target = mStartPoint;
443  int steps = mCommandTargetDistance / mCurrentMap.getResolution();
444  for(int i = 0; i < steps; i++)
445  {
446  unsigned int bestPoint = target;
447  std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(target);
448  for(unsigned int i = 0; i < neighbors.size(); i++)
449  {
450  if(mCurrentPlan[neighbors[i]] >= (unsigned int)0 && mCurrentPlan[neighbors[i]] < mCurrentPlan[bestPoint])
451  bestPoint = neighbors[i];
452  }
453  target = bestPoint;
454  }
455 
456  // Head towards (x,y)
457  unsigned int x = 0, y = 0;
458  if(!mCurrentMap.getCoordinates(x, y, target))
459  {
460  ROS_ERROR("Plan execution failed, target pose not in map!");
461  return false;
462  }
463  double map_angle = atan2((double)y - current_y, (double)x - current_x);
464 
465  double angle = map_angle - mCurrentDirection;
466  if(angle < -PI) angle += 2*PI;
467  if(angle > PI) angle -= 2*PI;
468 
469  // Create the command message
470  nav2d_operator::cmd msg;
471  msg.Turn = -2.0 * angle / PI;
472  if(msg.Turn < -1) msg.Turn = -1;
473  if(msg.Turn > 1) msg.Turn = 1;
474 
475  if(mCurrentPlan[mStartPoint] > mNavigationHomingDistance || mStatus == NAV_ST_EXPLORING)
476  msg.Mode = 0;
477  else
478  msg.Mode = 1;
479 
480  if(mCurrentPlan[mStartPoint] > 1.0 || mCurrentPlan[mStartPoint] < 0)
481  {
482  msg.Velocity = 1.0;
483  }else
484  {
485  msg.Velocity = 0.5 + (mCurrentPlan[mStartPoint] / 2.0);
486  }
487  mCommandPublisher.publish(msg);
488  return true;
489 }
490 
491 void RobotNavigator::receiveGetMapGoal(const nav2d_navigator::GetFirstMapGoal::ConstPtr &goal)
492 {
493  if(mStatus != NAV_ST_IDLE)
494  {
495  ROS_WARN("Navigator is busy!");
496  mGetMapActionServer->setAborted();
497  return;
498  }
499 
500  // Move the robot slowly ahead
501  mStatus = NAV_ST_RECOVERING;
502  nav2d_operator::cmd msg;
503  msg.Turn = 0;
504  msg.Velocity = 1.0;
505  msg.Mode = 0;
506 
507  nav2d_navigator::GetFirstMapFeedback f;
508 
509  Rate loopRate(mFrequency);
510  unsigned int cycles = 0;
511  while(true)
512  {
513  if(!ok() || mGetMapActionServer->isPreemptRequested() || mIsStopped)
514  {
515  ROS_INFO("GetFirstMap has been preempted externally.");
516  mGetMapActionServer->setPreempted();
517  stop();
518  return;
519  }
520 
521  if(cycles >= 4*mFrequency) break;
522  cycles++;
523 
524  mGetMapActionServer->publishFeedback(f);
525  mCommandPublisher.publish(msg);
526  spinOnce();
527  loopRate.sleep();
528  }
529 
530  if(!getMap() || !setCurrentPosition())
531  {
532  mGetMapActionServer->setAborted();
533  stop();
534  return;
535  }
536 
537  // Do a full turn to have a initial map
538  msg.Turn = 1;
539  msg.Mode = 1;
540  double lastDirection = mCurrentDirection;
541  double turn = 0;
542  while(true)
543  {
544  if(!ok() || mGetMapActionServer->isPreemptRequested() || mIsStopped)
545  {
546  ROS_INFO("GetFirstMap has been preempted externally.");
547  mGetMapActionServer->setPreempted();
548  stop();
549  return;
550  }
551 
552  setCurrentPosition();
553  double deltaTheta = mCurrentDirection - lastDirection;
554  while(deltaTheta < -PI) deltaTheta += 2*PI;
555  while(deltaTheta > PI) deltaTheta -= 2*PI;
556  turn += deltaTheta;
557  lastDirection = mCurrentDirection;
558  if(turn > 2*PI || turn < -2*PI)
559  {
560  break;
561  }
562 
563  mGetMapActionServer->publishFeedback(f);
564  mCommandPublisher.publish(msg);
565  spinOnce();
566  loopRate.sleep();
567  }
568 
569  stop();
570  mHasNewMap = false;
571 
572  if(getMap() && setCurrentPosition())
573  {
574  mGetMapActionServer->setSucceeded();
575  }else
576  {
577  ROS_WARN("Navigator could not be initialized!");
578  mGetMapActionServer->setAborted();
579  }
580 }
581 
582 void RobotNavigator::receiveLocalizeGoal(const nav2d_navigator::LocalizeGoal::ConstPtr &goal)
583 {
584  if(mStatus != NAV_ST_IDLE)
585  {
586  ROS_WARN("[Localize] Action aborted, Navigator is busy!");
587  mGetMapActionServer->setAborted();
588  return;
589  }
590 
591  // Move the robot slowly ahead
592  mStatus = NAV_ST_RECOVERING;
593  nav2d_operator::cmd msg;
594  msg.Turn = 0;
595  msg.Velocity = goal->velocity;
596  msg.Mode = 0;
597 
598  nav2d_navigator::LocalizeFeedback f;
599 
600  mHasNewMap = false;
601  Rate loopRate(1);
602  while(true)
603  {
604  // Check if we are asked to preempt
605  if(!ok() || mLocalizeActionServer->isPreemptRequested() || mIsStopped)
606  {
607  ROS_INFO("[Localize] Action has been preempted externally.");
608  mLocalizeActionServer->setPreempted();
609  stop();
610  return;
611  }
612 
613  if(mHasNewMap)
614  {
615  mCommandPublisher.publish(msg);
616  }else
617  {
618  getMap();
619  }
620 
621  // Check if we are localized successfully
622  if(isLocalized())
623  {
624  ROS_INFO("[Localize] Action succeeded.");
625  mLocalizeActionServer->setSucceeded();
626  stop();
627  return;
628  }
629 
630  mLocalizeActionServer->publishFeedback(f);
631  spinOnce();
632  loopRate.sleep();
633  }
634 }
635 
636 void RobotNavigator::receiveMoveGoal(const nav2d_navigator::MoveToPosition2DGoal::ConstPtr &goal)
637 {
638  if(mStatus != NAV_ST_IDLE)
639  {
640  ROS_WARN("Navigator is busy!");
641  mMoveActionServer->setAborted();
642  return;
643  }
644 
645  ROS_DEBUG("Received Goal: %.2f, %.2f (in frame '%s')", goal->target_pose.x, goal->target_pose.y, goal->header.frame_id.c_str());
646 
647  // Start navigating according to the generated plan
648  Rate loopRate(mFrequency);
649  unsigned int cycle = 0;
650  bool reached = false;
651  int recheckCycles = mMinReplanningPeriod * mFrequency;
652 
653  double targetDistance = (goal->target_distance > 0) ? goal->target_distance : mNavigationGoalDistance;
654  double targetAngle = (goal->target_angle > 0) ? goal->target_angle : mNavigationGoalAngle;
655 
656  while(true)
657  {
658  // Check if we are asked to preempt
659  if(!ok() || mMoveActionServer->isPreemptRequested() || mIsStopped)
660  {
661  ROS_INFO("Navigation has been preempted externally.");
662  mMoveActionServer->setPreempted();
663  stop();
664  return;
665  }
666 
667  // Constantly replan every 3 seconds
668  if(cycle == 0 || (recheckCycles && cycle % recheckCycles == 0))
669  {
670  WallTime startTime = WallTime::now();
671  mStatus = NAV_ST_NAVIGATING;
672 
673  // Create the plan for navigation
674  mHasNewMap = false;
675  if(!preparePlan())
676  {
677  ROS_ERROR("Prepare failed!");
678  mMoveActionServer->setAborted();
679  stop();
680  return;
681  }
682 
683  int mapX = (double)(goal->target_pose.x - mCurrentMap.getOriginX()) / mCurrentMap.getResolution();
684  int mapY = (double)(goal->target_pose.y - mCurrentMap.getOriginY()) / mCurrentMap.getResolution();
685  if(mapX < 0) mapX = 0;
686  if(mapX >= (int)mCurrentMap.getWidth()) mapX = mCurrentMap.getWidth() - 1;
687  if(mapY < 0) mapY = 0;
688  if(mapY >= (int)mCurrentMap.getHeight()) mapY = mCurrentMap.getHeight() - 1;
689 
690  bool success = false;
691  if(mCurrentMap.getIndex(mapX, mapY, mGoalPoint))
692  success = createPlan();
693 
694  if(!success)
695  {
696  if(correctGoalPose())
697  success = createPlan();
698  }
699 
700  if(!success)
701  {
702  ROS_ERROR("Planning failed!");
703  mMoveActionServer->setAborted();
704  stop();
705  return;
706  }
707 
708  WallTime endTime = WallTime::now();
709  WallDuration d = endTime - startTime;
710  ROS_INFO("Path planning took %.09f seconds, distance is %.2f m.", d.toSec(), mCurrentPlan[mStartPoint]);
711  }
712 
713  // Where are we now
714  mHasNewMap = false;
715  if(!setCurrentPosition())
716  {
717  ROS_ERROR("Navigation failed, could not get current position.");
718  mMoveActionServer->setAborted();
719  stop();
720  return;
721  }
722 
723  // Are we already close enough?
724  if(!reached && mCurrentPlan[mStartPoint] <= targetDistance && mCurrentPlan[mStartPoint] >= 0)
725  {
726  ROS_INFO("Reached target, now turning to desired direction.");
727  reached = true;
728  }
729 
730  if(reached)
731  {
732  // Are we also headed correctly?
733  double deltaTheta = mCurrentDirection - goal->target_pose.theta;
734  while(deltaTheta < -PI) deltaTheta += 2*PI;
735  while(deltaTheta > PI) deltaTheta -= 2*PI;
736 
737  double diff = (deltaTheta > 0) ? deltaTheta : -deltaTheta;
738  ROS_INFO_THROTTLE(1.0,"Heading: %.2f / Desired: %.2f / Difference: %.2f / Tolerance: %.2f", mCurrentDirection, goal->target_pose.theta, diff, targetAngle);
739  if(diff <= targetAngle)
740  {
741  ROS_INFO("Final Heading: %.2f / Desired: %.2f / Difference: %.2f / Tolerance: %.2f", mCurrentDirection, goal->target_pose.theta, diff, targetAngle);
742  break;
743  }
744 
745  nav2d_operator::cmd msg;
746  if(deltaTheta > 0)
747  {
748  msg.Turn = 1;
749  msg.Velocity = deltaTheta;
750  }else
751  {
752  msg.Turn = -1;
753  msg.Velocity = -deltaTheta;
754  }
755  if(msg.Velocity > 1) msg.Velocity = 1;
756  msg.Mode = 1;
757 
758  mCommandPublisher.publish(msg);
759  }else
760  {
761  generateCommand();
762  }
763 
764  // Publish feedback via ActionServer
765  if(cycle%10 == 0)
766  {
767  nav2d_navigator::MoveToPosition2DFeedback fb;
768  fb.distance = mCurrentPlan[mStartPoint];
769  mMoveActionServer->publishFeedback(fb);
770  }
771 
772  // Sleep remaining time
773  cycle++;
774  spinOnce();
775  loopRate.sleep();
776  if(loopRate.cycleTime() > ros::Duration(1.0 / mFrequency))
777  ROS_WARN("Missed desired rate of %.2fHz! Loop actually took %.4f seconds!",mFrequency, loopRate.cycleTime().toSec());
778  }
779 
780  // Set ActionServer suceeded
781  ROS_INFO("Goal reached.");
782  nav2d_navigator::MoveToPosition2DResult r;
783  r.final_pose.x = mCurrentPositionX;
784  r.final_pose.y = mCurrentPositionY;
785  r.final_pose.theta = mCurrentDirection;
786  r.final_distance = mCurrentPlan[mStartPoint];
787  mMoveActionServer->setSucceeded(r);
788  stop();
789 
790 }
791 
792 void RobotNavigator::receiveExploreGoal(const nav2d_navigator::ExploreGoal::ConstPtr &goal)
793 {
794  if(mStatus != NAV_ST_IDLE)
795  {
796  ROS_WARN("Navigator is busy!");
797  mExploreActionServer->setAborted();
798  return;
799  }
800 
801  mStatus = NAV_ST_EXPLORING;
802  unsigned int cycle = 0;
803  unsigned int lastCheck = 0;
804  unsigned int recheckCycles = mMinReplanningPeriod * mFrequency;
805  unsigned int recheckThrottle = mMaxReplanningPeriod * mFrequency;
806 
807  // Move to exploration target
808  Rate loopRate(mFrequency);
809  while(true)
810  {
811  // Check if we are asked to preempt
812  if(!ok() || mExploreActionServer->isPreemptRequested() || mIsStopped)
813  {
814  ROS_INFO("Exploration has been preempted externally.");
815  mExploreActionServer->setPreempted();
816  stop();
817  return;
818  }
819 
820  // Where are we now
821  mHasNewMap = false;
822  if(!setCurrentPosition())
823  {
824  ROS_ERROR("Exploration failed, could not get current position.");
825  mExploreActionServer->setAborted();
826  stop();
827  return;
828  }
829 
830  // Regularly recheck for exploration target
831  bool reCheck = lastCheck == 0 || (recheckCycles && (cycle - lastCheck > recheckCycles));
832  bool planOk = mCurrentPlan && mCurrentPlan[mStartPoint] >= 0;
833  bool nearGoal = planOk && ((cycle - lastCheck) > recheckThrottle && mCurrentPlan[mStartPoint] <= mExplorationGoalDistance);
834 
835  if(reCheck || nearGoal)
836  {
837  WallTime startTime = WallTime::now();
838  lastCheck = cycle;
839 
840  bool success = false;
841  if(preparePlan())
842  {
843  int result = mExplorationPlanner->findExplorationTarget(&mCurrentMap, mStartPoint, mGoalPoint);
844  switch(result)
845  {
846  case EXPL_TARGET_SET:
847  success = createPlan();
848  mStatus = NAV_ST_EXPLORING;
849  break;
850  case EXPL_FINISHED:
851  {
852  nav2d_navigator::ExploreResult r;
853  r.final_pose.x = mCurrentPositionX;
854  r.final_pose.y = mCurrentPositionY;
855  r.final_pose.theta = mCurrentDirection;
856  mExploreActionServer->setSucceeded(r);
857  }
858  stop();
859  ROS_INFO("Exploration has finished.");
860  return;
861  case EXPL_WAITING:
862  mStatus = NAV_ST_WAITING;
863  {
864  nav2d_operator::cmd stopMsg;
865  stopMsg.Turn = 0;
866  stopMsg.Velocity = 0;
867  mCommandPublisher.publish(stopMsg);
868  }
869  ROS_INFO("Exploration is waiting.");
870  break;
871  case EXPL_FAILED:
872  break;
873  default:
874  ROS_ERROR("Exploration planner returned invalid status code: %d!", result);
875  }
876  }
877 
878  if(mStatus == NAV_ST_EXPLORING)
879  {
880  if(success)
881  {
882  WallTime endTime = WallTime::now();
883  WallDuration d = endTime - startTime;
884  ROS_DEBUG("Exploration planning took %.09f seconds, distance is %.2f m.", d.toSec(), mCurrentPlan[mStartPoint]);
885  }else
886  {
887  mExploreActionServer->setAborted();
888  stop();
889  ROS_WARN("Exploration has failed!");
890  return;
891  }
892  }
893  }
894 
895  if(mStatus == NAV_ST_EXPLORING)
896  {
897  // Publish feedback via ActionServer
898  if(cycle%10 == 0)
899  {
900  nav2d_navigator::ExploreFeedback fb;
901  fb.distance = mCurrentPlan[mStartPoint];
902  fb.robot_pose.x = mCurrentPositionX;
903  fb.robot_pose.y = mCurrentPositionY;
904  fb.robot_pose.theta = mCurrentDirection;
905  mExploreActionServer->publishFeedback(fb);
906  }
907 
908  // Create a new command and send it to Operator
909  generateCommand();
910  }
911 
912  // Sleep remaining time
913  cycle++;
914  spinOnce();
915  loopRate.sleep();
916  if(loopRate.cycleTime() > ros::Duration(1.0 / mFrequency))
917  ROS_WARN("Missed desired rate of %.2fHz! Loop actually took %.4f seconds!",mFrequency, loopRate.cycleTime().toSec());
918  }
919 }
920 
922 {
923  return mTfListener.waitForTransform(mMapFrame, mRobotFrame, Time::now(), Duration(0.1));
924 }
925 
927 {
928  StampedTransform transform;
929  try
930  {
931  mTfListener.lookupTransform(mMapFrame, mRobotFrame, Time(0), transform);
932  }catch(TransformException ex)
933  {
934  ROS_ERROR("Could not get robot position: %s", ex.what());
935  return false;
936  }
937  double world_x = transform.getOrigin().x();
938  double world_y = transform.getOrigin().y();
939  double world_theta = getYaw(transform.getRotation());
940 
941  unsigned int current_x = (world_x - mCurrentMap.getOriginX()) / mCurrentMap.getResolution();
942  unsigned int current_y = (world_y - mCurrentMap.getOriginY()) / mCurrentMap.getResolution();
943  unsigned int i;
944 
945  if(!mCurrentMap.getIndex(current_x, current_y, i))
946  {
947  if(mHasNewMap || !getMap() || !mCurrentMap.getIndex(current_x, current_y, i))
948  {
949  ROS_ERROR("Is the robot out of the map?");
950  return false;
951  }
952  }
953  mStartPoint = i;
954  mCurrentDirection = world_theta;
955  mCurrentPositionX = world_x;
956  mCurrentPositionY = world_y;
957  return true;
958 }
d
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool receiveStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
#define NAV_PAUSE_SERVICE
Definition: commands.h:6
void receiveExploreGoal(const nav2d_navigator::ExploreGoal::ConstPtr &goal)
f
#define EXPL_WAITING
#define NAV_STOP_SERVICE
Definition: commands.h:5
std::pair< double, unsigned int > Entry
#define NAV_ST_WAITING
Definition: commands.h:20
Duration cycleTime() const
#define NAV_ST_NAVIGATING
Definition: commands.h:18
#define NAV_ST_IDLE
Definition: commands.h:17
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
#define NAV_MOVE_ACTION
Definition: commands.h:12
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
#define NAV_LOCALIZE_ACTION
Definition: commands.h:15
std::multimap< double, unsigned int > Queue
#define EXPL_FINISHED
TFSIMD_FORCE_INLINE const tfScalar & x() const
pluginlib::ClassLoader< ExplorationPlanner > PlanLoader
double distance(double x0, double y0, double x1, double y1)
#define ROS_INFO_THROTTLE(period,...)
#define NAV_ST_EXPLORING
Definition: commands.h:19
#define ROS_WARN_THROTTLE(period,...)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
actionlib::SimpleActionServer< nav2d_navigator::ExploreAction > ExploreActionServer
#define EXPL_TARGET_SET
void receiveGetMapGoal(const nav2d_navigator::GetFirstMapGoal::ConstPtr &goal)
#define NAV_GETMAP_ACTION
Definition: commands.h:14
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
double getYaw(const tf2::Quaternion &q)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void receiveLocalizeGoal(const nav2d_navigator::LocalizeGoal::ConstPtr &goal)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
bool sleep()
void receiveMoveGoal(const nav2d_navigator::MoveToPosition2DGoal::ConstPtr &goal)
actionlib::SimpleActionServer< nav2d_navigator::GetFirstMapAction > GetMapActionServer
static WallTime now()
Quaternion getRotation() const
#define EXPL_FAILED
double diff(double v1, double v2)
static Time now()
#define NAV_ST_RECOVERING
Definition: commands.h:21
bool receivePause(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
actionlib::SimpleActionServer< nav2d_navigator::LocalizeAction > LocalizeActionServer
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
actionlib::SimpleActionServer< nav2d_navigator::MoveToPosition2DAction > MoveActionServer
#define PI
#define NAV_EXPLORE_ACTION
Definition: commands.h:13
#define ROS_DEBUG(...)


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:43