00001 #include <robot_navigator/RobotNavigator.h>
00002 #include <robot_navigator/ExplorationPlanner.h>
00003 #include <robot_operator/cmd.h>
00004 #include <nav_msgs/GridCells.h>
00005 #include <visualization_msgs/Marker.h>
00006
00007 #include <set>
00008 #include <map>
00009
00010 #define PI 3.14159265
00011 #define FREQUENCY 5.0
00012
00013 using namespace ros;
00014 using namespace tf;
00015
00016 RobotNavigator::RobotNavigator()
00017 {
00018 NodeHandle robotNode;
00019
00020 std::string serviceName;
00021 robotNode.param("map_service", serviceName, std::string("get_map"));
00022 mGetMapClient = robotNode.serviceClient<nav_msgs::GetMap>(serviceName);
00023
00024 mCommandPublisher = robotNode.advertise<robot_operator::cmd>("cmd", 1);
00025 mCommandServer = robotNode.advertiseService(NAV_COMMAND_SERVICE, &RobotNavigator::receiveCommand, this);
00026 mCurrentPlan = NULL;
00027
00028 NodeHandle navigatorNode("~/");
00029 mPlanPublisher = navigatorNode.advertise<nav_msgs::GridCells>("plan", 1);
00030 mMarkerPublisher = navigatorNode.advertise<visualization_msgs::Marker>("markers", 1, true);
00031
00032
00033 navigatorNode.param("map_inflation_radius", mInflationRadius, 1.0);
00034 navigatorNode.param("robot_radius", mRobotRadius, 0.3);
00035 navigatorNode.param("exploration_strategy", mExplorationStrategy, std::string("exploration/NearestFrontier"));
00036 navigatorNode.param("navigation_goal_distance", mNavigationGoalDistance, 1.0);
00037 navigatorNode.param("navigation_goal_angle", mNavigationGoalAngle, 1.0);
00038 navigatorNode.param("exploration_goal_distance", mExplorationGoalDistance, 3.0);
00039 navigatorNode.param("navigation_homing_distance", mNavigationHomingDistance, 3.0);
00040 navigatorNode.param("min_replanning_period", mMinReplanningPeriod, 3.0);
00041 navigatorNode.param("max_replanning_period", mMaxReplanningPeriod, 1.0);
00042 mCostObstacle = 100;
00043 mCostLethal = (1.0 - (mRobotRadius / mInflationRadius)) * (double)mCostObstacle;
00044
00045 robotNode.param("map_frame", mMapFrame, std::string("map"));
00046 robotNode.param("robot_frame", mRobotFrame, std::string("robot"));
00047 robotNode.param("robot_id", mRobotID, 1);
00048 robotNode.param("move_action_topic", mMoveActionTopic, std::string(NAV_MOVE_ACTION));
00049 robotNode.param("explore_action_topic", mExploreActionTopic, std::string(NAV_EXPLORE_ACTION));
00050 robotNode.param("getmap_action_topic", mGetMapActionTopic, std::string(NAV_GETMAP_ACTION));
00051 robotNode.param("localize_action_topic", mLocalizeActionTopic, std::string(NAV_LOCALIZE_ACTION));
00052
00053
00054 std::string tfPrefix = mTfListener.getTFPrefix();
00055 mRobotFrame = resolve(tfPrefix, mRobotFrame);
00056 mMapFrame = resolve(tfPrefix, mMapFrame);
00057
00058 try
00059 {
00060 mPlanLoader = new PlanLoader("robot_navigator", "ExplorationLoader");
00061 mExplorationPlanner = mPlanLoader->createInstance(mExplorationStrategy);
00062 ROS_INFO("Successfully loaded exploration strategy [%s].", mExplorationStrategy.c_str());
00063
00064 mExploreActionServer = new ExploreActionServer(mExploreActionTopic, boost::bind(&RobotNavigator::receiveExploreGoal, this, _1), false);
00065 mExploreActionServer->start();
00066 }
00067 catch(pluginlib::PluginlibException& ex)
00068 {
00069 ROS_ERROR("Failed to load exploration plugin! Error: %s", ex.what());
00070 mExploreActionServer = NULL;
00071 mPlanLoader = NULL;
00072 }
00073
00074
00075 mMoveActionServer = new MoveActionServer(mMoveActionTopic, boost::bind(&RobotNavigator::receiveMoveGoal, this, _1), false);
00076 mMoveActionServer->start();
00077
00078 mLocalizeActionServer = new LocalizeActionServer(mLocalizeActionTopic, boost::bind(&RobotNavigator::receiveLocalizeGoal, this, _1), false);
00079 mLocalizeActionServer->start();
00080
00081 if(mRobotID == 1)
00082 {
00083 mGetMapActionServer = new GetMapActionServer(mGetMapActionTopic, boost::bind(&RobotNavigator::receiveGetMapGoal, this, _1), false);
00084 mGetMapActionServer->start();
00085 }
00086
00087 mHasNewMap = false;
00088 mIsStopped = false;
00089 mIsPaused = false;
00090 mStatus = NAV_ST_IDLE;
00091 mCellInflationRadius = 0;
00092 }
00093
00094 RobotNavigator::~RobotNavigator()
00095 {
00096 delete[] mCurrentPlan;
00097 delete mMoveActionServer;
00098 delete mExploreActionServer;
00099 delete mMoveActionServer;
00100 delete mPlanLoader;
00101 }
00102
00103 bool RobotNavigator::getMap()
00104 {
00105 if(mHasNewMap) return true;
00106
00107 if(!mGetMapClient.isValid())
00108 {
00109 ROS_ERROR("GetMap-Client is invalid!");
00110 return false;
00111 }
00112
00113 nav_msgs::GetMap srv;
00114 if(!mGetMapClient.call(srv))
00115 {
00116 ROS_INFO("Could not get a map.");
00117 return false;
00118 }
00119 mCurrentMap.update(srv.response.map);
00120
00121 if(mCurrentPlan) delete[] mCurrentPlan;
00122 mCurrentPlan = new double[mCurrentMap.getSize()];
00123
00124 if(mCellInflationRadius == 0)
00125 {
00126 ROS_INFO("Navigator is now initialized.");
00127 mCellInflationRadius = mInflationRadius / mCurrentMap.getResolution();
00128 mCellRobotRadius = mRobotRadius / mCurrentMap.getResolution();
00129 mInflationTool.computeCaches(mCellInflationRadius);
00130 mCurrentMap.setLethalCost(mCostLethal);
00131 }
00132
00133 mHasNewMap = true;
00134 return true;
00135 }
00136
00137 bool RobotNavigator::receiveCommand(robot_navigator::SendCommand::Request &req, robot_navigator::SendCommand::Response &res)
00138 {
00139 robot_operator::cmd stopMsg;
00140 stopMsg.Turn = 0;
00141 stopMsg.Velocity = 0;
00142
00143 switch(req.command)
00144 {
00145 case NAV_COM_STOP:
00146 mIsStopped = true;
00147 break;
00148
00149 case NAV_COM_PAUSE:
00150 if(mIsPaused)
00151 {
00152 mIsPaused = false;
00153 res.response = NAV_RES_OK;
00154 }else
00155 {
00156 mIsPaused = true;
00157 mCommandPublisher.publish(stopMsg);
00158 res.response = NAV_RES_OK;
00159 }
00160 break;
00161
00162 default:
00163 ROS_ERROR("Invalid command!");
00164 res.response = NAV_RES_INVALID;
00165 }
00166 return true;
00167 }
00168
00169 typedef std::multimap<double,unsigned int> Queue;
00170 typedef std::pair<double,unsigned int> Entry;
00171
00172 bool RobotNavigator::preparePlan()
00173 {
00174
00175 if(!getMap())
00176 {
00177 if(mCellInflationRadius == 0) return false;
00178 ROS_WARN("Could not get a new map, trying to go with the old one...");
00179 }
00180
00181
00182 if(!setCurrentPosition()) return false;
00183
00184
00185 unsigned int x = 0, y = 0;
00186 if(mCurrentMap.getCoordinates(x, y, mStartPoint))
00187 for(int i = -mCellRobotRadius; i < (int)mCellRobotRadius; i++)
00188 for(int j = -mCellRobotRadius; j < (int)mCellRobotRadius; j++)
00189 mCurrentMap.setData(x+i, y+j, 0);
00190
00191 mInflationTool.inflateMap(&mCurrentMap);
00192 return true;
00193 }
00194
00195 bool RobotNavigator::createPlan()
00196 {
00197 ROS_DEBUG("Map-Value of goal point is %d, lethal threshold is %d.", mCurrentMap.getData(mGoalPoint), mCostLethal);
00198
00199 unsigned int goal_x = 0, goal_y = 0;
00200 if(mCurrentMap.getCoordinates(goal_x,goal_y,mGoalPoint))
00201 {
00202 visualization_msgs::Marker marker;
00203 marker.header.frame_id = "/map";
00204 marker.header.stamp = ros::Time();
00205 marker.id = 0;
00206 marker.type = visualization_msgs::Marker::CYLINDER;
00207 marker.action = visualization_msgs::Marker::ADD;
00208 marker.pose.position.x = mCurrentMap.getOriginX() + (((double)goal_x+0.5) * mCurrentMap.getResolution());
00209 marker.pose.position.y = mCurrentMap.getOriginY() + (((double)goal_y+0.5) * mCurrentMap.getResolution());
00210 marker.pose.position.z = 0.5;
00211 marker.pose.orientation.x = 0.0;
00212 marker.pose.orientation.y = 0.0;
00213 marker.pose.orientation.z = 0.0;
00214 marker.pose.orientation.w = 1.0;
00215 marker.scale.x = mCurrentMap.getResolution() * 3.0;
00216 marker.scale.y = mCurrentMap.getResolution() * 3.0;
00217 marker.scale.z = 1.0;
00218 marker.color.a = 1.0;
00219 marker.color.r = 1.0;
00220 marker.color.g = 0.0;
00221 marker.color.b = 0.0;
00222 mMarkerPublisher.publish(marker);
00223 }else
00224 {
00225 ROS_ERROR("Couldn't ressolve goal point coordinates!");
00226 }
00227
00228 Queue queue;
00229
00230
00231 int mapSize = mCurrentMap.getSize();
00232 for(int i = 0; i < mapSize; i++)
00233 {
00234 mCurrentPlan[i] = -1;
00235 }
00236
00237 if(mCurrentMap.isFree(mGoalPoint))
00238 {
00239 queue.insert(Entry(0.0, mGoalPoint));
00240 mCurrentPlan[mGoalPoint] = 0;
00241 }else
00242 {
00243
00244 int reach = mCellRobotRadius + (1.0 / mCurrentMap.getResolution());
00245 std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(mGoalPoint, reach);
00246 for(unsigned int i = 0; i < neighbors.size(); i++)
00247 {
00248 queue.insert(Entry(0.0, neighbors[i]));
00249 mCurrentPlan[neighbors[i]] = 0;
00250 }
00251 }
00252
00253 Queue::iterator next;
00254 double distance;
00255 unsigned int x, y, index;
00256 double linear = mCurrentMap.getResolution();
00257 double diagonal = std::sqrt(2.0) * linear;
00258
00259
00260 while(!queue.empty())
00261 {
00262
00263 next = queue.begin();
00264 distance = next->first;
00265 index = next->second;
00266 queue.erase(next);
00267
00268 if(mCurrentPlan[index] >= 0 && mCurrentPlan[index] < distance) continue;
00269
00270
00271
00272
00273 if(!mCurrentMap.getCoordinates(x, y, index)) continue;
00274 std::vector<unsigned int> ind;
00275 ind.push_back(index - 1);
00276 ind.push_back(index + 1);
00277 ind.push_back(index - mCurrentMap.getWidth());
00278 ind.push_back(index + mCurrentMap.getWidth());
00279 ind.push_back(index - mCurrentMap.getWidth() - 1);
00280 ind.push_back(index - mCurrentMap.getWidth() + 1);
00281 ind.push_back(index + mCurrentMap.getWidth() - 1);
00282 ind.push_back(index + mCurrentMap.getWidth() + 1);
00283
00284 for(unsigned int it = 0; it < ind.size(); it++)
00285 {
00286 unsigned int i = ind[it];
00287 if(mCurrentMap.isFree(i))
00288 {
00289 double delta = (it < 4) ? linear : diagonal;
00290 double newDistance = distance + delta + (10 * delta * (double)mCurrentMap.getData(i) / (double)mCostObstacle);
00291 if(mCurrentPlan[i] == -1 || newDistance < mCurrentPlan[i])
00292 {
00293 queue.insert(Entry(newDistance, i));
00294 mCurrentPlan[i] = newDistance;
00295 }
00296 }
00297 }
00298 }
00299
00300 if(mCurrentPlan[mStartPoint] < 0)
00301 {
00302 ROS_ERROR("No way between robot and goal!");
00303 return false;
00304 }
00305
00306 publishPlan();
00307 return true;
00308 }
00309
00310 void RobotNavigator::publishPlan()
00311 {
00312 nav_msgs::GridCells plan_msg;
00313 plan_msg.header.frame_id = mMapFrame.c_str();
00314 plan_msg.header.stamp = Time::now();
00315
00316 plan_msg.cell_width = mCurrentMap.getResolution();
00317 plan_msg.cell_height = mCurrentMap.getResolution();
00318
00319 unsigned int index = mStartPoint;
00320 std::vector<std::pair<double, double> > points;
00321 while(true)
00322 {
00323 unsigned int x = 0, y = 0;
00324 if(mCurrentMap.getCoordinates(x,y,index))
00325 points.push_back(std::pair<double, double>(
00326 ((x+0.5) * mCurrentMap.getResolution()) + mCurrentMap.getOriginX(),
00327 ((y+0.5) * mCurrentMap.getResolution()) + mCurrentMap.getOriginY()
00328 ));
00329
00330 if(mCurrentPlan[index] == 0) break;
00331
00332 unsigned int next_index = index;
00333
00334 std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(index);
00335 for(unsigned int i = 0; i < neighbors.size(); i++)
00336 {
00337 if(mCurrentPlan[neighbors[i]] >= 0 && mCurrentPlan[neighbors[i]] < mCurrentPlan[next_index])
00338 next_index = neighbors[i];
00339 }
00340
00341 if(index == next_index) break;
00342 index = next_index;
00343 }
00344
00345 plan_msg.cells.resize(points.size());
00346 for(unsigned int i = 0; i < points.size(); i++)
00347 {
00348 plan_msg.cells[i].x = points[i].first;
00349 plan_msg.cells[i].y = points[i].second;
00350 plan_msg.cells[i].z = 0.0;
00351 }
00352 mPlanPublisher.publish(plan_msg);
00353 }
00354
00355 bool RobotNavigator::correctGoalPose()
00356 {
00357
00358 int mapSize = mCurrentMap.getSize();
00359 for(int i = 0; i < mapSize; i++)
00360 {
00361 mCurrentPlan[i] = -1;
00362 }
00363
00364
00365 Queue queue;
00366 Entry goal(0.0, mGoalPoint);
00367 queue.insert(goal);
00368 mCurrentPlan[mGoalPoint] = 0;
00369
00370 Queue::iterator next;
00371 double linear = mCurrentMap.getResolution();
00372
00373
00374 while(!queue.empty())
00375 {
00376
00377 next = queue.begin();
00378 double distance = next->first;
00379 unsigned int index = next->second;
00380 queue.erase(next);
00381
00382 if(mCurrentPlan[index] >= 0 && mCurrentPlan[index] < distance) continue;
00383
00384
00385 std::vector<unsigned int> neighbors = mCurrentMap.getNeighbors(index);
00386 for(unsigned int i = 0; i < neighbors.size(); i++)
00387 {
00388 if(mCurrentMap.isFree(neighbors[i]))
00389 {
00390 mGoalPoint = neighbors[i];
00391 return true;
00392 }else
00393 {
00394 double newDistance = distance + linear;
00395 if(mCurrentPlan[neighbors[i]] == -1)
00396 {
00397 queue.insert(Entry(newDistance, neighbors[i]));
00398 mCurrentPlan[neighbors[i]] = newDistance;
00399 }
00400 }
00401 }
00402 }
00403 return false;
00404 }
00405
00406 void RobotNavigator::stop()
00407 {
00408 robot_operator::cmd stopMsg;
00409 stopMsg.Turn = 0;
00410 stopMsg.Velocity = 0;
00411 mCommandPublisher.publish(stopMsg);
00412 mStatus = NAV_ST_IDLE;
00413 mIsPaused = false;
00414 mIsStopped = false;
00415 }
00416
00417 bool RobotNavigator::generateCommand()
00418 {
00419
00420 if(mIsPaused)
00421 {
00422 ROS_INFO_THROTTLE(1.0, "Navigator is paused and will not move now.");
00423 return true;
00424 }
00425
00426 if(mStatus != NAV_ST_NAVIGATING && mStatus != NAV_ST_EXPLORING)
00427 {
00428 ROS_WARN_THROTTLE(1.0, "Navigator has status %d when generateCommand() was called!", mStatus);
00429 return false;
00430 }
00431
00432
00433 unsigned int current_x = 0, current_y = 0;
00434 if(!mCurrentMap.getCoordinates(current_x, current_y, mStartPoint))
00435 {
00436 ROS_ERROR("Plan execution failed, robot not in map!");
00437 return false;
00438 }
00439
00440 unsigned int target = mStartPoint;
00441 int steps = 1.0 / mCurrentMap.getResolution();
00442 for(int i = 0; i < steps; i++)
00443 {
00444 unsigned int bestPoint = target;
00445 std::vector<unsigned int> neighbors = mCurrentMap.getFreeNeighbors(target);
00446 for(unsigned int i = 0; i < neighbors.size(); i++)
00447 {
00448 if(mCurrentPlan[neighbors[i]] >= (unsigned int)0 && mCurrentPlan[neighbors[i]] < mCurrentPlan[bestPoint])
00449 bestPoint = neighbors[i];
00450 }
00451 target = bestPoint;
00452 }
00453
00454
00455 unsigned int x = 0, y = 0;
00456 if(!mCurrentMap.getCoordinates(x, y, target))
00457 {
00458 ROS_ERROR("Plan execution failed, target pose not in map!");
00459 return false;
00460 }
00461 double map_angle = atan2((double)y - current_y, (double)x - current_x);
00462
00463 double angle = map_angle - mCurrentDirection;
00464 if(angle < -PI) angle += 2*PI;
00465 if(angle > PI) angle -= 2*PI;
00466
00467
00468 robot_operator::cmd msg;
00469 msg.Turn = -2.0 * angle / PI;
00470 if(msg.Turn < -1) msg.Turn = -1;
00471 if(msg.Turn > 1) msg.Turn = 1;
00472
00473 if(mCurrentPlan[mStartPoint] > mNavigationHomingDistance || mStatus == NAV_ST_EXPLORING)
00474 msg.Mode = 0;
00475 else
00476 msg.Mode = 1;
00477
00478 if(mCurrentPlan[mStartPoint] > 1.0 || mCurrentPlan[mStartPoint] < 0)
00479 {
00480 msg.Velocity = 1.0;
00481 }else
00482 {
00483 msg.Velocity = 0.5 + (mCurrentPlan[mStartPoint] / 2.0);
00484 }
00485 mCommandPublisher.publish(msg);
00486 return true;
00487 }
00488
00489 void RobotNavigator::receiveGetMapGoal(const robot_navigator::GetFirstMapGoal::ConstPtr &goal)
00490 {
00491 if(mStatus != NAV_ST_IDLE)
00492 {
00493 ROS_WARN("Navigator is busy!");
00494 mGetMapActionServer->setAborted();
00495 return;
00496 }
00497
00498
00499 mStatus = NAV_ST_RECOVERING;
00500 robot_operator::cmd msg;
00501 msg.Turn = 0;
00502 msg.Velocity = 1.0;
00503 msg.Mode = 0;
00504
00505 robot_navigator::GetFirstMapFeedback f;
00506
00507 Rate loopRate(FREQUENCY);
00508 unsigned int cycles = 0;
00509 while(true)
00510 {
00511 if(!ok() || mGetMapActionServer->isPreemptRequested() || mIsStopped)
00512 {
00513 ROS_INFO("GetFirstMap has been preempted externally.");
00514 mGetMapActionServer->setPreempted();
00515 stop();
00516 return;
00517 }
00518
00519 if(cycles >= 4*FREQUENCY) break;
00520 cycles++;
00521
00522 mGetMapActionServer->publishFeedback(f);
00523 mCommandPublisher.publish(msg);
00524 spinOnce();
00525 loopRate.sleep();
00526 }
00527
00528 if(!getMap() || !setCurrentPosition())
00529 {
00530 mGetMapActionServer->setAborted();
00531 stop();
00532 return;
00533 }
00534
00535
00536 msg.Turn = 1;
00537 msg.Mode = 1;
00538 double lastDirection = mCurrentDirection;
00539 double turn = 0;
00540 while(true)
00541 {
00542 if(!ok() || mGetMapActionServer->isPreemptRequested() || mIsStopped)
00543 {
00544 ROS_INFO("GetFirstMap has been preempted externally.");
00545 mGetMapActionServer->setPreempted();
00546 stop();
00547 return;
00548 }
00549
00550 setCurrentPosition();
00551 double deltaTheta = mCurrentDirection - lastDirection;
00552 while(deltaTheta < -PI) deltaTheta += 2*PI;
00553 while(deltaTheta > PI) deltaTheta -= 2*PI;
00554 turn += deltaTheta;
00555 lastDirection = mCurrentDirection;
00556 if(turn > 2*PI || turn < -2*PI)
00557 {
00558 break;
00559 }
00560
00561 mGetMapActionServer->publishFeedback(f);
00562 mCommandPublisher.publish(msg);
00563 spinOnce();
00564 loopRate.sleep();
00565 }
00566
00567 stop();
00568 mHasNewMap = false;
00569
00570 if(getMap() && setCurrentPosition())
00571 {
00572 mGetMapActionServer->setSucceeded();
00573 }else
00574 {
00575 ROS_WARN("Navigator could not be initialized!");
00576 mGetMapActionServer->setAborted();
00577 }
00578 }
00579
00580 void RobotNavigator::receiveLocalizeGoal(const robot_navigator::LocalizeGoal::ConstPtr &goal)
00581 {
00582 if(mStatus != NAV_ST_IDLE)
00583 {
00584 ROS_WARN("[Localize] Action aborted, Navigator is busy!");
00585 mGetMapActionServer->setAborted();
00586 return;
00587 }
00588
00589
00590 mStatus = NAV_ST_RECOVERING;
00591 robot_operator::cmd msg;
00592 msg.Turn = 0;
00593 msg.Velocity = goal->velocity;
00594 msg.Mode = 0;
00595
00596 robot_navigator::LocalizeFeedback f;
00597
00598 mHasNewMap = false;
00599 Rate loopRate(1);
00600 while(true)
00601 {
00602
00603 if(!ok() || mLocalizeActionServer->isPreemptRequested() || mIsStopped)
00604 {
00605 ROS_INFO("[Localize] Action has been preempted externally.");
00606 mLocalizeActionServer->setPreempted();
00607 stop();
00608 return;
00609 }
00610
00611 if(mHasNewMap)
00612 {
00613 mCommandPublisher.publish(msg);
00614 }else
00615 {
00616 getMap();
00617 }
00618
00619
00620 if(setCurrentPosition())
00621 {
00622 ROS_INFO("[Localize] Action succeeded.");
00623 mLocalizeActionServer->setSucceeded();
00624 stop();
00625 return;
00626 }
00627
00628 mLocalizeActionServer->publishFeedback(f);
00629 spinOnce();
00630 loopRate.sleep();
00631 }
00632 }
00633
00634 void RobotNavigator::receiveMoveGoal(const robot_navigator::MoveToPosition2DGoal::ConstPtr &goal)
00635 {
00636 if(mStatus != NAV_ST_IDLE)
00637 {
00638 ROS_WARN("Navigator is busy!");
00639 mMoveActionServer->setAborted();
00640 return;
00641 }
00642
00643 ROS_DEBUG("Received Goal: %.2f, %.2f (in frame '%s')", goal->target_pose.x, goal->target_pose.y, goal->header.frame_id.c_str());
00644
00645
00646 Rate loopRate(FREQUENCY);
00647 unsigned int cycle = 0;
00648 bool reached = false;
00649 int recheckCycles = mMinReplanningPeriod * FREQUENCY;
00650
00651 double targetDistance = (goal->target_distance > 0) ? goal->target_distance : mNavigationGoalDistance;
00652 double targetAngle = (goal->target_angle > 0) ? goal->target_angle : mNavigationGoalAngle;
00653
00654 while(true)
00655 {
00656
00657 if(!ok() || mMoveActionServer->isPreemptRequested() || mIsStopped)
00658 {
00659 ROS_INFO("Navigation has been preempted externally.");
00660 mMoveActionServer->setPreempted();
00661 stop();
00662 return;
00663 }
00664
00665
00666 if(cycle % recheckCycles == 0)
00667 {
00668 WallTime startTime = WallTime::now();
00669 mStatus = NAV_ST_NAVIGATING;
00670
00671
00672 mHasNewMap = false;
00673 if(!preparePlan())
00674 {
00675 ROS_ERROR("Prepare failed!");
00676 mMoveActionServer->setAborted();
00677 stop();
00678 return;
00679 }
00680
00681 int mapX = (double)(goal->target_pose.x - mCurrentMap.getOriginX()) / mCurrentMap.getResolution();
00682 int mapY = (double)(goal->target_pose.y - mCurrentMap.getOriginY()) / mCurrentMap.getResolution();
00683 if(mapX < 0) mapX = 0;
00684 if(mapX >= (int)mCurrentMap.getWidth()) mapX = mCurrentMap.getWidth() - 1;
00685 if(mapY < 0) mapY = 0;
00686 if(mapY >= (int)mCurrentMap.getHeight()) mapY = mCurrentMap.getHeight() - 1;
00687
00688 bool success = false;
00689 if(mCurrentMap.getIndex(mapX, mapY, mGoalPoint))
00690 success = createPlan();
00691
00692 if(!success)
00693 {
00694 if(correctGoalPose())
00695 success = createPlan();
00696 }
00697
00698 if(!success)
00699 {
00700 ROS_ERROR("Planning failed!");
00701 mMoveActionServer->setAborted();
00702 stop();
00703 return;
00704 }
00705
00706 WallTime endTime = WallTime::now();
00707 WallDuration d = endTime - startTime;
00708 ROS_INFO("Path planning took %.09f seconds, distance is %.2f m.", d.toSec(), mCurrentPlan[mStartPoint]);
00709 }
00710
00711
00712 mHasNewMap = false;
00713 if(!setCurrentPosition())
00714 {
00715 ROS_ERROR("Navigation failed, could not get current position.");
00716 mMoveActionServer->setAborted();
00717 stop();
00718 return;
00719 }
00720
00721
00722 if(!reached && mCurrentPlan[mStartPoint] <= targetDistance && mCurrentPlan[mStartPoint] >= 0)
00723 {
00724 ROS_INFO("Reached target, now turning to desired direction.");
00725 reached = true;
00726 }
00727
00728 if(reached)
00729 {
00730
00731 double deltaTheta = mCurrentDirection - goal->target_pose.theta;
00732 while(deltaTheta < -PI) deltaTheta += 2*PI;
00733 while(deltaTheta > PI) deltaTheta -= 2*PI;
00734
00735 double diff = (deltaTheta > 0) ? deltaTheta : -deltaTheta;
00736 ROS_INFO_THROTTLE(1.0,"Heading: %.2f / Desired: %.2f / Difference: %.2f / Tolerance: %.2f", mCurrentDirection, goal->target_pose.theta, diff, targetAngle);
00737 if(diff <= targetAngle)
00738 {
00739 ROS_INFO("Final Heading: %.2f / Desired: %.2f / Difference: %.2f / Tolerance: %.2f", mCurrentDirection, goal->target_pose.theta, diff, targetAngle);
00740 break;
00741 }
00742
00743 robot_operator::cmd msg;
00744 if(deltaTheta > 0)
00745 {
00746 msg.Turn = 1;
00747 msg.Velocity = deltaTheta;
00748 }else
00749 {
00750 msg.Turn = -1;
00751 msg.Velocity = -deltaTheta;
00752 }
00753 if(msg.Velocity > 1) msg.Velocity = 1;
00754 msg.Mode = 1;
00755
00756 mCommandPublisher.publish(msg);
00757 }else
00758 {
00759 generateCommand();
00760 }
00761
00762
00763 if(cycle%10 == 0)
00764 {
00765 robot_navigator::MoveToPosition2DFeedback fb;
00766 fb.distance = mCurrentPlan[mStartPoint];
00767 mMoveActionServer->publishFeedback(fb);
00768 }
00769
00770
00771 cycle++;
00772 spinOnce();
00773 loopRate.sleep();
00774 if(loopRate.cycleTime() > ros::Duration(1.0 / FREQUENCY))
00775 ROS_WARN("Missed desired rate of %.2fHz! Loop actually took %.4f seconds!",FREQUENCY, loopRate.cycleTime().toSec());
00776 }
00777
00778
00779 ROS_INFO("Goal reached.");
00780 robot_navigator::MoveToPosition2DResult r;
00781 r.final_pose.x = mCurrentPositionX;
00782 r.final_pose.y = mCurrentPositionY;
00783 r.final_pose.theta = mCurrentDirection;
00784 r.final_distance = mCurrentPlan[mStartPoint];
00785 mMoveActionServer->setSucceeded(r);
00786 stop();
00787
00788 }
00789
00790 void RobotNavigator::receiveExploreGoal(const robot_navigator::ExploreGoal::ConstPtr &goal)
00791 {
00792 if(mStatus != NAV_ST_IDLE)
00793 {
00794 ROS_WARN("Navigator is busy!");
00795 mExploreActionServer->setAborted();
00796 return;
00797 }
00798
00799 mStatus = NAV_ST_EXPLORING;
00800 unsigned int cycle = 0;
00801 unsigned int lastCheck = 0;
00802 unsigned int recheckCycles = mMinReplanningPeriod * FREQUENCY;
00803 unsigned int recheckThrottle = mMaxReplanningPeriod * FREQUENCY;
00804
00805
00806 Rate loopRate(FREQUENCY);
00807 while(true)
00808 {
00809
00810 if(!ok() || mExploreActionServer->isPreemptRequested() || mIsStopped)
00811 {
00812 ROS_INFO("Exploration has been preempted externally.");
00813 mExploreActionServer->setPreempted();
00814 stop();
00815 return;
00816 }
00817
00818
00819 mHasNewMap = false;
00820 if(!setCurrentPosition())
00821 {
00822 ROS_ERROR("Exploration failed, could not get current position.");
00823 mExploreActionServer->setAborted();
00824 stop();
00825 return;
00826 }
00827
00828
00829 cycle++;
00830 bool reCheck = lastCheck == 0 || cycle - lastCheck > recheckCycles;
00831 bool planOk = mCurrentPlan && mCurrentPlan[mStartPoint] >= 0;
00832 bool nearGoal = planOk && ((cycle - lastCheck) > recheckThrottle && mCurrentPlan[mStartPoint] <= mExplorationGoalDistance);
00833
00834 if(reCheck || nearGoal)
00835 {
00836 WallTime startTime = WallTime::now();
00837 lastCheck = cycle;
00838
00839 bool success = false;
00840 if(preparePlan())
00841 {
00842 int result = mExplorationPlanner->findExplorationTarget(&mCurrentMap, mStartPoint, mGoalPoint);
00843 switch(result)
00844 {
00845 case EXPL_TARGET_SET:
00846 success = createPlan();
00847 mStatus = NAV_ST_EXPLORING;
00848 break;
00849 case EXPL_FINISHED:
00850 {
00851 robot_navigator::ExploreResult r;
00852 r.final_pose.x = mCurrentPositionX;
00853 r.final_pose.y = mCurrentPositionY;
00854 r.final_pose.theta = mCurrentDirection;
00855 mExploreActionServer->setSucceeded(r);
00856 }
00857 stop();
00858 ROS_INFO("Exploration has finished.");
00859 return;
00860 case EXPL_WAITING:
00861 mStatus = NAV_ST_WAITING;
00862 {
00863 robot_operator::cmd stopMsg;
00864 stopMsg.Turn = 0;
00865 stopMsg.Velocity = 0;
00866 mCommandPublisher.publish(stopMsg);
00867 }
00868 ROS_INFO("Exploration is waiting.");
00869 break;
00870 case EXPL_FAILED:
00871 break;
00872 default:
00873 ROS_ERROR("Exploration planner returned invalid status code: %d!", result);
00874 }
00875 }
00876
00877 if(mStatus == NAV_ST_EXPLORING)
00878 {
00879 if(success)
00880 {
00881 WallTime endTime = WallTime::now();
00882 WallDuration d = endTime - startTime;
00883 ROS_DEBUG("Exploration planning took %.09f seconds, distance is %.2f m.", d.toSec(), mCurrentPlan[mStartPoint]);
00884 }else
00885 {
00886 mExploreActionServer->setAborted();
00887 stop();
00888 ROS_WARN("Exploration has failed!");
00889 return;
00890 }
00891 }
00892 }
00893
00894 if(mStatus == NAV_ST_EXPLORING)
00895 {
00896
00897 if(cycle%10 == 0)
00898 {
00899 robot_navigator::ExploreFeedback fb;
00900 fb.distance = mCurrentPlan[mStartPoint];
00901 fb.robot_pose.x = mCurrentPositionX;
00902 fb.robot_pose.y = mCurrentPositionY;
00903 fb.robot_pose.theta = mCurrentDirection;
00904 mExploreActionServer->publishFeedback(fb);
00905 }
00906
00907
00908 generateCommand();
00909 }
00910
00911
00912 spinOnce();
00913 loopRate.sleep();
00914 if(loopRate.cycleTime() > ros::Duration(1.0 / FREQUENCY))
00915 ROS_WARN("Missed desired rate of %.2fHz! Loop actually took %.4f seconds!",FREQUENCY, loopRate.cycleTime().toSec());
00916 }
00917 }
00918
00919 bool RobotNavigator::setCurrentPosition()
00920 {
00921 StampedTransform transform;
00922 try
00923 {
00924 mTfListener.lookupTransform(mMapFrame, mRobotFrame, Time(0), transform);
00925 }catch(TransformException ex)
00926 {
00927 ROS_ERROR("Could not get robot position: %s", ex.what());
00928 return false;
00929 }
00930 double world_x = transform.getOrigin().x();
00931 double world_y = transform.getOrigin().y();
00932 double world_theta = getYaw(transform.getRotation());
00933
00934 unsigned int current_x = (world_x - mCurrentMap.getOriginX()) / mCurrentMap.getResolution();
00935 unsigned int current_y = (world_y - mCurrentMap.getOriginY()) / mCurrentMap.getResolution();
00936 unsigned int i;
00937
00938 if(!mCurrentMap.getIndex(current_x, current_y, i))
00939 {
00940 if(mHasNewMap || !getMap() || !mCurrentMap.getIndex(current_x, current_y, i))
00941 {
00942 ROS_ERROR("Is the robot out of the map?");
00943 return false;
00944 }
00945 }
00946 mStartPoint = i;
00947 mCurrentDirection = world_theta;
00948 mCurrentPositionX = world_x;
00949 mCurrentPositionY = world_y;
00950 return true;
00951 }