1 #include <nav2d_operator/cmd.h> 2 #include <nav_msgs/GridCells.h> 3 #include <visualization_msgs/Marker.h> 20 std::string serviceName;
21 robotNode.
param(
"map_service", serviceName, std::string(
"get_map"));
22 mGetMapClient = robotNode.
serviceClient<nav_msgs::GetMap>(serviceName);
24 mCommandPublisher = robotNode.
advertise<nav2d_operator::cmd>(
"cmd", 1);
30 mPlanPublisher = navigatorNode.
advertise<nav_msgs::GridCells>(
"plan", 1);
31 mMarkerPublisher = navigatorNode.
advertise<visualization_msgs::Marker>(
"markers", 1,
true);
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);
46 mCostLethal = (1.0 - (mRobotRadius / mInflationRadius)) * (double)mCostObstacle;
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);
57 mRobotFrame = mTfListener.resolve(mRobotFrame);
58 mMapFrame = mTfListener.resolve(mMapFrame);
62 mPlanLoader =
new PlanLoader(
"nav2d_navigator",
"ExplorationPlanner");
63 mExplorationPlanner = mPlanLoader->createInstance(mExplorationStrategy);
64 ROS_INFO(
"Successfully loaded exploration strategy [%s].", mExplorationStrategy.c_str());
67 mExploreActionServer->start();
71 ROS_ERROR(
"Failed to load exploration plugin! Error: %s", ex.what());
72 mExploreActionServer = NULL;
78 mMoveActionServer->start();
81 mLocalizeActionServer->start();
86 mGetMapActionServer->start();
89 mGetMapActionServer = NULL;
96 mCellInflationRadius = 0;
101 delete[] mCurrentPlan;
102 delete mMoveActionServer;
103 delete mExploreActionServer;
104 delete mGetMapActionServer;
105 mExplorationPlanner.reset();
111 if(mHasNewMap)
return true;
113 if(!mGetMapClient.isValid())
119 nav_msgs::GetMap srv;
120 if(!mGetMapClient.call(srv))
125 mCurrentMap.update(srv.response.map);
127 if(mCurrentPlan)
delete[] mCurrentPlan;
128 mCurrentPlan =
new double[mCurrentMap.getSize()];
130 if(mCellInflationRadius == 0)
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);
147 res.message =
"Navigator received stop signal.";
157 res.message =
"Navigator continues.";
161 nav2d_operator::cmd stopMsg;
163 stopMsg.Velocity = 0;
164 mCommandPublisher.publish(stopMsg);
166 res.message =
"Navigator pauses.";
171 typedef std::multimap<double,unsigned int>
Queue;
172 typedef std::pair<double,unsigned int>
Entry;
179 if(mCellInflationRadius == 0)
return false;
180 ROS_WARN(
"Could not get a new map, trying to go with the old one...");
184 if(!setCurrentPosition())
return false;
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);
193 mInflationTool.inflateMap(&mCurrentMap);
199 ROS_DEBUG(
"Map-Value of goal point is %d, lethal threshold is %d.", mCurrentMap.getData(mGoalPoint), mCostLethal);
201 unsigned int goal_x = 0, goal_y = 0;
202 if(mCurrentMap.getCoordinates(goal_x,goal_y,mGoalPoint))
204 visualization_msgs::Marker marker;
205 marker.header.frame_id =
"/map";
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);
227 ROS_ERROR(
"Couldn't ressolve goal point coordinates!");
233 int mapSize = mCurrentMap.getSize();
234 for(
int i = 0; i < mapSize; i++)
236 mCurrentPlan[i] = -1;
239 if(mCurrentMap.isFree(mGoalPoint))
241 queue.insert(
Entry(0.0, mGoalPoint));
242 mCurrentPlan[mGoalPoint] = 0;
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++)
250 queue.insert(
Entry(0.0, neighbors[i]));
251 mCurrentPlan[neighbors[i]] = 0;
255 Queue::iterator next;
257 unsigned int x,
y, index;
258 double linear = mCurrentMap.getResolution();
259 double diagonal = std::sqrt(2.0) * linear;
262 while(!queue.empty())
265 next = queue.begin();
266 distance = next->first;
267 index = next->second;
270 if(mCurrentPlan[index] >= 0 && mCurrentPlan[index] < distance)
continue;
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);
286 for(
unsigned int it = 0; it < ind.size(); it++)
288 unsigned int i = ind[it];
289 if(mCurrentMap.isFree(i))
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])
295 queue.insert(
Entry(newDistance, i));
296 mCurrentPlan[i] = newDistance;
302 if(mCurrentPlan[mStartPoint] < 0)
304 ROS_ERROR(
"No way between robot and goal!");
314 nav_msgs::GridCells plan_msg;
315 plan_msg.header.frame_id = mMapFrame.c_str();
318 plan_msg.cell_width = mCurrentMap.getResolution();
319 plan_msg.cell_height = mCurrentMap.getResolution();
321 unsigned int index = mStartPoint;
322 std::vector<std::pair<double, double> > points;
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()
332 if(mCurrentPlan[index] == 0)
break;
334 unsigned int next_index = index;
336 std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(index);
337 for(
unsigned int i = 0; i < neighbors.size(); i++)
339 if(mCurrentPlan[neighbors[i]] >= 0 && mCurrentPlan[neighbors[i]] < mCurrentPlan[next_index])
340 next_index = neighbors[i];
343 if(index == next_index)
break;
347 plan_msg.cells.resize(points.size());
348 for(
unsigned int i = 0; i < points.size(); i++)
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;
354 mPlanPublisher.publish(plan_msg);
360 int mapSize = mCurrentMap.getSize();
361 for(
int i = 0; i < mapSize; i++)
363 mCurrentPlan[i] = -1;
368 Entry goal(0.0, mGoalPoint);
370 mCurrentPlan[mGoalPoint] = 0;
372 Queue::iterator next;
373 double linear = mCurrentMap.getResolution();
376 while(!queue.empty())
379 next = queue.begin();
381 unsigned int index = next->second;
384 if(mCurrentPlan[index] >= 0 && mCurrentPlan[index] < distance)
continue;
387 std::vector<unsigned int> neighbors = mCurrentMap.getNeighbors(index);
388 for(
unsigned int i = 0; i < neighbors.size(); i++)
390 if(mCurrentMap.isFree(neighbors[i]))
392 mGoalPoint = neighbors[i];
396 double newDistance = distance + linear;
397 if(mCurrentPlan[neighbors[i]] == -1)
399 queue.insert(
Entry(newDistance, neighbors[i]));
400 mCurrentPlan[neighbors[i]] = newDistance;
410 nav2d_operator::cmd stopMsg;
412 stopMsg.Velocity = 0;
413 mCommandPublisher.publish(stopMsg);
430 ROS_WARN_THROTTLE(1.0,
"Navigator has status %d when generateCommand() was called!", mStatus);
435 unsigned int current_x = 0, current_y = 0;
436 if(!mCurrentMap.getCoordinates(current_x, current_y, mStartPoint))
438 ROS_ERROR(
"Plan execution failed, robot not in map!");
442 unsigned int target = mStartPoint;
443 int steps = mCommandTargetDistance / mCurrentMap.getResolution();
444 for(
int i = 0; i < steps; i++)
446 unsigned int bestPoint = target;
447 std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(target);
448 for(
unsigned int i = 0; i < neighbors.size(); i++)
450 if(mCurrentPlan[neighbors[i]] >= (
unsigned int)0 && mCurrentPlan[neighbors[i]] < mCurrentPlan[bestPoint])
451 bestPoint = neighbors[i];
457 unsigned int x = 0,
y = 0;
458 if(!mCurrentMap.getCoordinates(x,
y, target))
460 ROS_ERROR(
"Plan execution failed, target pose not in map!");
463 double map_angle = atan2((
double)
y - current_y, (
double)x - current_x);
465 double angle = map_angle - mCurrentDirection;
466 if(angle < -
PI) angle += 2*
PI;
467 if(angle >
PI) angle -= 2*
PI;
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;
475 if(mCurrentPlan[mStartPoint] > mNavigationHomingDistance || mStatus ==
NAV_ST_EXPLORING)
480 if(mCurrentPlan[mStartPoint] > 1.0 || mCurrentPlan[mStartPoint] < 0)
485 msg.Velocity = 0.5 + (mCurrentPlan[mStartPoint] / 2.0);
487 mCommandPublisher.publish(msg);
496 mGetMapActionServer->setAborted();
502 nav2d_operator::cmd msg;
507 nav2d_navigator::GetFirstMapFeedback
f;
509 Rate loopRate(mFrequency);
510 unsigned int cycles = 0;
513 if(!
ok() || mGetMapActionServer->isPreemptRequested() || mIsStopped)
515 ROS_INFO(
"GetFirstMap has been preempted externally.");
516 mGetMapActionServer->setPreempted();
521 if(cycles >= 4*mFrequency)
break;
524 mGetMapActionServer->publishFeedback(f);
525 mCommandPublisher.publish(msg);
530 if(!getMap() || !setCurrentPosition())
532 mGetMapActionServer->setAborted();
540 double lastDirection = mCurrentDirection;
544 if(!
ok() || mGetMapActionServer->isPreemptRequested() || mIsStopped)
546 ROS_INFO(
"GetFirstMap has been preempted externally.");
547 mGetMapActionServer->setPreempted();
552 setCurrentPosition();
553 double deltaTheta = mCurrentDirection - lastDirection;
554 while(deltaTheta < -
PI) deltaTheta += 2*
PI;
555 while(deltaTheta >
PI) deltaTheta -= 2*
PI;
557 lastDirection = mCurrentDirection;
558 if(turn > 2*
PI || turn < -2*
PI)
563 mGetMapActionServer->publishFeedback(f);
564 mCommandPublisher.publish(msg);
572 if(getMap() && setCurrentPosition())
574 mGetMapActionServer->setSucceeded();
577 ROS_WARN(
"Navigator could not be initialized!");
578 mGetMapActionServer->setAborted();
586 ROS_WARN(
"[Localize] Action aborted, Navigator is busy!");
587 mGetMapActionServer->setAborted();
593 nav2d_operator::cmd msg;
595 msg.Velocity = goal->velocity;
598 nav2d_navigator::LocalizeFeedback
f;
605 if(!
ok() || mLocalizeActionServer->isPreemptRequested() || mIsStopped)
607 ROS_INFO(
"[Localize] Action has been preempted externally.");
608 mLocalizeActionServer->setPreempted();
615 mCommandPublisher.publish(msg);
624 ROS_INFO(
"[Localize] Action succeeded.");
625 mLocalizeActionServer->setSucceeded();
630 mLocalizeActionServer->publishFeedback(f);
641 mMoveActionServer->setAborted();
645 ROS_DEBUG(
"Received Goal: %.2f, %.2f (in frame '%s')", goal->target_pose.x, goal->target_pose.y, goal->header.frame_id.c_str());
648 Rate loopRate(mFrequency);
649 unsigned int cycle = 0;
650 bool reached =
false;
651 int recheckCycles = mMinReplanningPeriod * mFrequency;
653 double targetDistance = (goal->target_distance > 0) ? goal->target_distance : mNavigationGoalDistance;
654 double targetAngle = (goal->target_angle > 0) ? goal->target_angle : mNavigationGoalAngle;
659 if(!
ok() || mMoveActionServer->isPreemptRequested() || mIsStopped)
661 ROS_INFO(
"Navigation has been preempted externally.");
662 mMoveActionServer->setPreempted();
668 if(cycle == 0 || (recheckCycles && cycle % recheckCycles == 0))
678 mMoveActionServer->setAborted();
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;
690 bool success =
false;
691 if(mCurrentMap.getIndex(mapX, mapY, mGoalPoint))
692 success = createPlan();
696 if(correctGoalPose())
697 success = createPlan();
703 mMoveActionServer->setAborted();
710 ROS_INFO(
"Path planning took %.09f seconds, distance is %.2f m.", d.
toSec(), mCurrentPlan[mStartPoint]);
715 if(!setCurrentPosition())
717 ROS_ERROR(
"Navigation failed, could not get current position.");
718 mMoveActionServer->setAborted();
724 if(!reached && mCurrentPlan[mStartPoint] <= targetDistance && mCurrentPlan[mStartPoint] >= 0)
726 ROS_INFO(
"Reached target, now turning to desired direction.");
733 double deltaTheta = mCurrentDirection - goal->target_pose.theta;
734 while(deltaTheta < -
PI) deltaTheta += 2*
PI;
735 while(deltaTheta >
PI) deltaTheta -= 2*
PI;
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)
741 ROS_INFO(
"Final Heading: %.2f / Desired: %.2f / Difference: %.2f / Tolerance: %.2f", mCurrentDirection, goal->target_pose.theta, diff, targetAngle);
745 nav2d_operator::cmd msg;
749 msg.Velocity = deltaTheta;
753 msg.Velocity = -deltaTheta;
755 if(msg.Velocity > 1) msg.Velocity = 1;
758 mCommandPublisher.publish(msg);
767 nav2d_navigator::MoveToPosition2DFeedback fb;
768 fb.distance = mCurrentPlan[mStartPoint];
769 mMoveActionServer->publishFeedback(fb);
777 ROS_WARN(
"Missed desired rate of %.2fHz! Loop actually took %.4f seconds!",mFrequency, loopRate.cycleTime().toSec());
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);
797 mExploreActionServer->setAborted();
802 unsigned int cycle = 0;
803 unsigned int lastCheck = 0;
804 unsigned int recheckCycles = mMinReplanningPeriod * mFrequency;
805 unsigned int recheckThrottle = mMaxReplanningPeriod * mFrequency;
808 Rate loopRate(mFrequency);
812 if(!
ok() || mExploreActionServer->isPreemptRequested() || mIsStopped)
814 ROS_INFO(
"Exploration has been preempted externally.");
815 mExploreActionServer->setPreempted();
822 if(!setCurrentPosition())
824 ROS_ERROR(
"Exploration failed, could not get current position.");
825 mExploreActionServer->setAborted();
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);
835 if(reCheck || nearGoal)
840 bool success =
false;
843 int result = mExplorationPlanner->findExplorationTarget(&mCurrentMap, mStartPoint, mGoalPoint);
847 success = createPlan();
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);
859 ROS_INFO(
"Exploration has finished.");
864 nav2d_operator::cmd stopMsg;
866 stopMsg.Velocity = 0;
867 mCommandPublisher.publish(stopMsg);
869 ROS_INFO(
"Exploration is waiting.");
874 ROS_ERROR(
"Exploration planner returned invalid status code: %d!", result);
884 ROS_DEBUG(
"Exploration planning took %.09f seconds, distance is %.2f m.", d.
toSec(), mCurrentPlan[mStartPoint]);
887 mExploreActionServer->setAborted();
889 ROS_WARN(
"Exploration has failed!");
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);
917 ROS_WARN(
"Missed desired rate of %.2fHz! Loop actually took %.4f seconds!",mFrequency, loopRate.
cycleTime().
toSec());
923 return mTfListener.waitForTransform(mMapFrame, mRobotFrame,
Time::now(),
Duration(0.1));
931 mTfListener.lookupTransform(mMapFrame, mRobotFrame,
Time(0), transform);
934 ROS_ERROR(
"Could not get robot position: %s", ex.what());
941 unsigned int current_x = (world_x - mCurrentMap.getOriginX()) / mCurrentMap.getResolution();
942 unsigned int current_y = (world_y - mCurrentMap.getOriginY()) / mCurrentMap.getResolution();
945 if(!mCurrentMap.getIndex(current_x, current_y, i))
947 if(mHasNewMap || !getMap() || !mCurrentMap.getIndex(current_x, current_y, i))
949 ROS_ERROR(
"Is the robot out of the map?");
954 mCurrentDirection = world_theta;
955 mCurrentPositionX = world_x;
956 mCurrentPositionY = world_y;
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
void receiveExploreGoal(const nav2d_navigator::ExploreGoal::ConstPtr &goal)
std::pair< double, unsigned int > Entry
Duration cycleTime() const
#define NAV_ST_NAVIGATING
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
#define NAV_LOCALIZE_ACTION
std::multimap< double, unsigned int > Queue
TFSIMD_FORCE_INLINE const tfScalar & x() const
pluginlib::ClassLoader< ExplorationPlanner > PlanLoader
bool setCurrentPosition()
double distance(double x0, double y0, double x1, double y1)
#define ROS_INFO_THROTTLE(period,...)
#define ROS_WARN_THROTTLE(period,...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
actionlib::SimpleActionServer< nav2d_navigator::ExploreAction > ExploreActionServer
void receiveGetMapGoal(const nav2d_navigator::GetFirstMapGoal::ConstPtr &goal)
#define NAV_GETMAP_ACTION
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)
void receiveMoveGoal(const nav2d_navigator::MoveToPosition2DGoal::ConstPtr &goal)
actionlib::SimpleActionServer< nav2d_navigator::GetFirstMapAction > GetMapActionServer
double diff(double v1, double v2)
#define NAV_ST_RECOVERING
bool receivePause(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
actionlib::SimpleActionServer< nav2d_navigator::LocalizeAction > LocalizeActionServer
ROSCPP_DECL void spinOnce()
actionlib::SimpleActionServer< nav2d_navigator::MoveToPosition2DAction > MoveActionServer
#define NAV_EXPLORE_ACTION