00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <topological_roadmap/move_base_topo.h>
00038 #include <graph_mapping_utils/geometry.h>
00039 #include <topological_nav_msgs/RoadmapPath.h>
00040 #include <graph_mapping_utils/to_string.h>
00041 #include <boost/lexical_cast.hpp>
00042 #include <topological_map_2d/ros_conversion.h>
00043 #include <topological_roadmap/ros_conversion.h>
00044 #include <topological_nav_msgs/SwitchGrid.h>
00045 #include <set>
00046
00047 namespace topological_roadmap
00048
00049 {
00050
00051 namespace gm=geometry_msgs;
00052 namespace wh=warehouse;
00053 namespace nm=nav_msgs;
00054 namespace gmu=graph_mapping_utils;
00055 namespace tmap=topological_map_2d;
00056 namespace msg=topological_nav_msgs;
00057
00058 using std::vector;
00059 using std::set;
00060 using std::string;
00061 using std::list;
00062
00063 typedef boost::mutex::scoped_lock Lock;
00064
00065 MoveBaseTopo::MoveBaseTopo():
00066 db_("topological_navigation"), grids_(db_.setupCollection<nm::OccupancyGrid>("grids")),
00067 as_(ros::NodeHandle(), "move_base_topo", boost::bind(&MoveBaseTopo::executeCB, this, _1), false),
00068 costmap_("costmap", tf_), move_base_client_("move_base", true), grid_switch_(false)
00069 {
00070 ros::NodeHandle n;
00071 ros::NodeHandle private_nh("~");
00072
00073 private_nh.param("progress_check_frequency", progress_check_frequency_, 5.0);
00074 private_nh.param("next_waypoint_distance", next_waypoint_distance_, 1.0);
00075 private_nh.param("planner_patience", planner_patience_, 10.0);
00076
00077 double block_check_period;
00078 private_nh.param("block_check_period", block_check_period, 1.0);
00079 private_nh.param("blocked_edge_timeout", blocked_edge_timeout_, 0.0);
00080
00081 last_valid_plan_ = ros::Time::now();
00082
00083
00084 ros::NodeHandle prefix_nh;
00085 tf_prefix_ = tf::getPrefixParam(prefix_nh);
00086
00087 planner_.initialize("planner", &costmap_);
00088 costmap_.stop();
00089 roadmap_sub_ = n.subscribe("topological_roadmap", 1,
00090 &MoveBaseTopo::roadmapCB, this);
00091 localization_sub_ = n.subscribe("topological_localization", 1,
00092 &MoveBaseTopo::localizationCB, this);
00093 grid_update_sub_ = n.subscribe("warehouse/topological_navigation/grids/notify",
00094 100, &MoveBaseTopo::gridUpdateCB, this);
00095 tmap_sub_ = n.subscribe("topological_graph", 1, &MoveBaseTopo::graphCB, this);
00096 path_pub_ = n.advertise<msg::RoadmapPath>("roadmap_path", 5);
00097 edge_watchdog_ = n.createTimer(ros::Duration(block_check_period),
00098 &MoveBaseTopo::checkEdgeTimeouts, this);
00099 make_plan_client_ =
00100 n.serviceClient<nm::GetPlan>("move_base_node/make_plan");
00101 switch_grid_client_ =
00102 n.serviceClient<msg::SwitchGrid>("switch_local_grid");
00103 as_.start();
00104 ROS_INFO ("move_base_topo initialization complete");
00105 }
00106
00107 void MoveBaseTopo::graphCB (const msg::TopologicalGraph::ConstPtr m)
00108 {
00109 Lock l(mutex_);
00110 tmap_ = tmap::fromMessage(*m);
00111 }
00112
00113 void MoveBaseTopo::cleanup()
00114 {
00115
00116 ROS_DEBUG_NAMED("exec", "Clearing blocked edges");
00117 blocked_edges_.clear();
00118 costmap_.stop();
00119 }
00120
00121 gm::PoseStamped MoveBaseTopo::nodePoseOnGrid (const unsigned n, const unsigned g) const
00122 {
00123 gm::PoseStamped pose;
00124 pose.header.frame_id = tmap::gridFrame(g);
00125 pose.pose.position = positionOnGrid(n, g, roadmap_, tmap_);
00126 pose.pose.orientation.w = 1.0;
00127 return pose;
00128 }
00129
00130 bool MoveBaseTopo::robotWithinTolerance(double tolerance_dist, unsigned node_id)
00131 {
00132
00133 tf::Stamped<tf::Pose> robot_pose;
00134 if(!costmap_.getRobotPose(robot_pose)){
00135 ROS_ERROR("Cannot get the current pose of the robot, checking whether or not the robot is close enough to its next waypoint will fail. This is likely a tf problem");
00136 return false;
00137 }
00138 gm::PoseStamped robot_pose_msg;
00139 tf::poseStampedTFToMsg(robot_pose, robot_pose_msg);
00140
00141
00142 const unsigned g = tmap::frameGrid(costmap_.getGlobalFrameID());
00143 const gm::PoseStamped node_pose = nodePoseOnGrid(node_id, g);
00144 double sq_dist = squareDist(robot_pose_msg, node_pose);
00145 if(sq_dist < (tolerance_dist * tolerance_dist))
00146 return true;
00147
00148 return false;
00149 }
00150
00151 unsigned MoveBaseTopo::lastWaypointOnGridIndex (const vector<unsigned>& plan,
00152 const unsigned g) const
00153 {
00154
00155 vector<unsigned> current_nodes_vec =
00156 nodesOnGrid(g, roadmap_, tmap_).first;
00157 set<unsigned> current_nodes(current_nodes_vec.begin(),
00158 current_nodes_vec.end());
00159
00160 ROS_DEBUG_STREAM_NAMED ("last_waypoint_on_grid",
00161 "Finding last waypoint for grid " << g <<
00162 " with nodes " << gmu::toString(current_nodes_vec));
00163 unsigned int furthest_valid = 0;
00164 for(unsigned int i = 0; i < plan.size(); ++i)
00165 {
00166 ROS_DEBUG_NAMED ("last_waypoint_on_grid", "Furthest valid is %u",
00167 furthest_valid);
00168
00169 if(gmu::contains(current_nodes, plan[i]))
00170 {
00171
00172 gm::PoseStamped node_pose = nodePoseOnGrid(plan[i], g);
00173 if(planner_.validPointPotential(node_pose.pose.position))
00174 furthest_valid = i;
00175 }
00176 else
00177
00178 break;
00179 }
00180 ROS_DEBUG_NAMED ("last_waypoint_on_grid", "Final furthest valid is %u",
00181 furthest_valid);
00182 return furthest_valid;
00183 }
00184
00185
00186 unsigned MoveBaseTopo::lastWaypointOnGridIndex(const Path& plan,
00187 const string& global_frame)
00188 {
00189 return lastWaypointOnGridIndex(plan.first, tmap::frameGrid(global_frame));
00190 }
00191
00192 bool MoveBaseTopo::makeRoadmapPlan(const msg::MoveBaseTopoGoal::ConstPtr& goal,
00193 boost::optional<Path>& plan, string& error_string)
00194 {
00195 plan.reset();
00196 unsigned best_id(0);
00197 double best_dist = DBL_MAX;
00198
00199
00200 tf::Stamped<tf::Pose> robot_pose;
00201 if(!costmap_.getRobotPose(robot_pose)){
00202 error_string = "Cannot navigate anywhere because the costmap could not get the current pose of the robot. Likely a tf problem.";
00203 return false;
00204 }
00205 else if (!current_grid_)
00206 {
00207 error_string = "Don't have a current grid yet, so can't make a plan.";
00208 return false;
00209 }
00210
00211
00212 gm::Point robot_point;
00213 robot_point.x = robot_pose.getOrigin().x();
00214 robot_point.y = robot_pose.getOrigin().y();
00215
00216
00217 planner_.computePotential(robot_point);
00218
00219
00220 std::vector<unsigned> contained_nodes = nodesOnGrid(*current_grid_, roadmap_, tmap_).first;
00221
00222 BOOST_FOREACH (const unsigned n, contained_nodes)
00223 {
00224 const unsigned g = tmap::frameGrid(costmap_.getGlobalFrameID());
00225 const gm::PoseStamped node_pose = nodePoseOnGrid(n, g);
00226
00227
00228 double path_dist = shortestPathDistance(node_pose.pose);
00229 if(path_dist < best_dist){
00230 best_dist = path_dist;
00231 best_id = n;
00232 }
00233 }
00234
00235 if(best_dist == DBL_MAX)
00236 {
00237 error_string = "Cannot navigate anywhere because the robot cannot be projected onto a valid node.";
00238 return false;
00239 }
00240
00241 ROS_DEBUG_STREAM("The closest node is node " << best_id <<
00242 ", planning from this to node " << goal->goal_node);
00243
00244
00245 ResultPtr res = shortestPaths(roadmap_, best_id);
00246 plan = extractPath(res, goal->goal_node);
00247 if(!plan)
00248 {
00249 std::stringstream error_msg;
00250 error_msg << "Failed to find a plan between node: " << best_id << " and node: " << goal->goal_node;
00251 error_string = error_msg.str();
00252 return false;
00253 }
00254
00255 return true;
00256 }
00257
00258 void MoveBaseTopo::checkEdgeTimeouts(const ros::TimerEvent& e)
00259 {
00260 Lock l(mutex_);
00261
00262 for(list<BlockedEdge>::iterator blocked_it = blocked_edges_.begin(); blocked_it != blocked_edges_.end();){
00263 if(blocked_edge_timeout_ > 0.0 && blocked_it->blocked_time + ros::Duration(blocked_edge_timeout_) < ros::Time::now()){
00264 ROS_ERROR("Unblocking edge");
00265 blocked_it = blocked_edges_.erase(blocked_it);
00266 }
00267 else
00268 ++blocked_it;
00269 }
00270 }
00271
00272 void MoveBaseTopo::removeBlockedEdges(const list<BlockedEdge>& blocked_edges, Roadmap& roadmap)
00273 {
00274 BOOST_FOREACH (const BlockedEdge& blocked, blocked_edges)
00275 {
00276 const GraphVertex v = roadmap.node(blocked.from);
00277 const GraphVertex w = roadmap.node(blocked.to);
00278 vector<unsigned> edges_to_delete;
00279
00280
00281 BOOST_FOREACH (GraphEdge e, edge_range(v, w, roadmap))
00282 edges_to_delete.push_back(roadmap[e].id);
00283 BOOST_FOREACH (const unsigned id, edges_to_delete)
00284 roadmap.deleteEdge(id);
00285 }
00286 }
00287
00288 unsigned MoveBaseTopo::bestGrid (const vector<unsigned>& plan) const
00289 {
00290 ROS_ASSERT(!plan.empty());
00291 const unsigned start = plan[0];
00292 set<unsigned> candidates;
00293 const unsigned g0 = roadmap_.nodeInfo(start).grid;
00294 candidates.insert(g0);
00295 BOOST_FOREACH (const tmap::GraphVertex& v,
00296 adjacent_vertices(tmap_.node(g0), tmap_))
00297 candidates.insert(tmap_[v].id);
00298
00299 unsigned best_grid=-1;
00300 int best_val = -1;
00301 BOOST_FOREACH (const unsigned g, candidates)
00302 {
00303 const int val = lastWaypointOnGridIndex(plan, g);
00304 ROS_INFO ("Grid %u has %d waypoints", g, val);
00305 if (val > best_val)
00306 {
00307 best_val = val;
00308 best_grid = g;
00309 }
00310 }
00311 ROS_ASSERT(best_grid>0);
00312 return best_grid;
00313 }
00314
00315 void MoveBaseTopo::executeCB(const msg::MoveBaseTopoGoal::ConstPtr& goal)
00316 {
00317 ROS_DEBUG_NAMED("exec", "Received a goal, starting costmap");
00318 move_base_client_.waitForServer();
00319 costmap_.start();
00320 ROS_DEBUG_NAMED("exec", "costmap started");
00321
00322
00323 boost::optional<Path> plan;
00324 string error_string;
00325
00326 unsigned int current_waypoint = 0;
00327 bool finished_plan = false;
00328 last_valid_plan_ = ros::Time::now();
00329
00330
00331 while(ros::ok() && !finished_plan){
00332 move_base_msgs::MoveBaseGoal mb_goal;
00333 {
00334
00335 Lock l(mutex_);
00336
00337
00338
00339
00340 ROS_DEBUG_NAMED("exec", "Planning");
00341 if(!makeRoadmapPlan(goal, plan, error_string)){
00342 if(ros::Time::now() > last_valid_plan_ + ros::Duration(planner_patience_)){
00343 ROS_WARN("In loop planning: %s, now: %.3f, last: %.3f, finish: %.2f", error_string.c_str(), ros::Time::now().toSec(),
00344 last_valid_plan_.toSec(), (last_valid_plan_ + ros::Duration(planner_patience_)).toSec());
00345 as_.setAborted(msg::MoveBaseTopoResult(), error_string);
00346 cleanup();
00347 return;
00348 }
00349 ROS_WARN_THROTTLE(1.0, "Failed to make a plan in roadmap: %s, trying again.", error_string.c_str());
00350
00351 continue;
00352 }
00353
00354
00355
00356 last_valid_plan_ = ros::Time::now();
00357 ROS_DEBUG_STREAM_NAMED("exec", "Found roadmap plan: "
00358 << gmu::toString(plan->first));
00359 msg::RoadmapPath msg;
00360 msg.path = plan->first;
00361 path_pub_.publish(msg);
00362 const unsigned best_grid = bestGrid(plan->first);
00363
00364
00365 msg::SwitchGrid srv;
00366 srv.request.grid = best_grid;
00367 if (!switch_grid_client_.call(srv))
00368 ROS_WARN ("Service call to switch_grid failed");
00369 ROS_DEBUG_NAMED("exec", "Requesting switch to grid %u", best_grid);
00370 unsigned i=0;
00371 while (ros::ok() && i++<20 && tmap::frameGrid(costmap_.getGlobalFrameID())!=best_grid)
00372 {
00373 ROS_DEBUG_NAMED("exec", "Waiting for costmap to catch up on grid switch");
00374 ros::Duration(0.1).sleep();
00375 }
00376
00377
00378 string global_frame = costmap_.getGlobalFrameID();
00379 current_waypoint = lastWaypointOnGridIndex(*plan, global_frame);
00380 grid_switch_ = false;
00381
00382
00383 gm::PoseStamped node_pose = nodePoseOnGrid(plan->first[current_waypoint],
00384 tmap::frameGrid(global_frame));
00385 ROS_DEBUG_STREAM_NAMED("exec", "Aiming for waypoint " <<
00386 plan->first[current_waypoint] <<
00387 " at " << gmu::toString(node_pose.pose) << " on "
00388 << tmap::frameGrid(global_frame));
00389
00390 mb_goal.target_pose = node_pose;
00391 move_base_client_.sendGoal(mb_goal);
00392 }
00393
00394
00395 ros::Rate r(progress_check_frequency_);
00396 bool close_enough = false;
00397 while(ros::ok() && !move_base_client_.getState().isDone() &&!close_enough)
00398 {
00399 {
00400 Lock l(mutex_);
00401
00402 if(current_waypoint < plan->first.size() - 1 &&
00403 (grid_switch_ || robotWithinTolerance(next_waypoint_distance_,
00404 plan->first[current_waypoint])))
00405 {
00406 ROS_DEBUG_COND_NAMED (grid_switch_, "exec", "Switching to grid %u",
00407 *current_grid_);
00408 close_enough = true;
00409
00410 last_valid_plan_ = ros::Time::now();
00411 }
00412 ROS_DEBUG_THROTTLE_NAMED (2.0, "exec", "Waiting for waypoint %u;",
00413 plan->first[current_waypoint]);
00414 }
00415
00416 r.sleep();
00417 }
00418
00419
00420 bool not_going_anywhere = false;
00421 if ((plan->first[current_waypoint] == plan->first[0] &&
00422 plan->first[current_waypoint] != plan->first[plan->first.size() -1])
00423 && move_base_client_.getState().isDone())
00424 {
00425 not_going_anywhere = true;
00426 }
00427
00428
00429
00430
00431
00432 ROS_DEBUG_NAMED("exec", "Not going anywhere: %d, client state: %s; "
00433 "Close_enough is %d", not_going_anywhere,
00434 move_base_client_.getState().toString().c_str(), close_enough);
00435 if(!close_enough || not_going_anywhere){
00436 if(not_going_anywhere || move_base_client_.getState() != actionlib::SimpleClientGoalState::SUCCEEDED){
00437
00438
00439
00440 bool edge_cut = false;
00441
00442 unsigned int check_node = 0;
00443 while(check_node <= current_waypoint && check_node < plan->first.size() - 1 && !edge_cut){
00444 ROS_ERROR("Trying to prune");
00445
00446 nm::GetPlan mb_plan;
00447
00448
00449 const unsigned g = tmap::frameGrid(costmap_.getGlobalFrameID());
00450
00451 const gm::PoseStamped check_node_pose =
00452 nodePoseOnGrid(plan->first[check_node], g);
00453 const gm::PoseStamped next_node_pose =
00454 nodePoseOnGrid(plan->first[check_node+1], g);
00455
00456 mb_plan.request.start = check_node_pose;
00457 mb_plan.request.goal = next_node_pose;
00458
00459
00460 if(!make_plan_client_.call(mb_plan) ||
00461 mb_plan.response.plan.poses.empty())
00462 {
00463 Lock l(mutex_);
00464 blocked_edges_.push_back(BlockedEdge(plan->first[check_node],
00465 plan->first[check_node + 1],
00466 ros::Time::now()));
00467 ROS_DEBUG_NAMED("exec", "Adding a blocked edge for %u->%u",
00468 plan->first[check_node],
00469 plan->first[check_node + 1]);
00470
00471 removeBlockedEdges(blocked_edges_, roadmap_);
00472 edge_cut = true;
00473 }
00474 ++check_node;
00475 }
00476
00477
00478 if(edge_cut)
00479 continue;
00480 else if(not_going_anywhere){
00481 Lock l(mutex_);
00482 blocked_edges_.push_back(BlockedEdge(plan->first[0], plan->first[1],
00483 ros::Time::now()));
00484 ROS_ERROR("Adding a blocked edge for %u->%u",
00485 plan->first[0], plan->first[1]);
00486
00487 removeBlockedEdges(blocked_edges_, roadmap_);
00488 continue;
00489 }
00490
00491 std::stringstream error_msg;
00492 error_msg << "MoveBase failed to make it to node" << plan->first[current_waypoint] << " state is " << move_base_client_.getState().toString();
00493 ROS_ERROR("%s", error_msg.str().c_str());
00494 as_.setAborted(msg::MoveBaseTopoResult(), error_msg.str());
00495 cleanup();
00496 return;
00497 }
00498 else
00499 ROS_DEBUG("Made it to node: %u", plan->first[current_waypoint]);
00500 }
00501
00502
00503 if(current_waypoint == plan->first.size() - 1)
00504 finished_plan = true;
00505 }
00506
00507
00508 if(move_base_client_.getState() != actionlib::SimpleClientGoalState::SUCCEEDED){
00509 std::stringstream error_msg;
00510 error_msg << "MoveBase failed to make it to node" << plan->first[plan->first.size() - 1] << " state is " << move_base_client_.getState().toString();
00511 ROS_ERROR("%s", error_msg.str().c_str());
00512 as_.setAborted(msg::MoveBaseTopoResult(), error_msg.str());
00513 cleanup();
00514 return;
00515 }
00516
00517 ROS_INFO("Made it to the goal location");
00518 as_.setSucceeded();
00519 cleanup();
00520 }
00521
00522 double MoveBaseTopo::shortestPathDistance(const gm::Pose& p1)
00523 {
00524 gm::PoseStamped goal;
00525 goal.header.frame_id = costmap_.getGlobalFrameID();
00526 goal.header.stamp = ros::Time::now();
00527 goal.pose = p1;
00528
00529 vector<gm::PoseStamped> plan;
00530
00531
00532
00533 if(!planner_.getPlanFromPotential(goal, plan) || plan.size() <= 1){
00534 return DBL_MAX;
00535 }
00536
00537 double length = 0.0;
00538 for(unsigned int i = 0; i < plan.size() - 1; ++i){
00539 length += gmu::euclideanDistance(plan[i].pose.position, plan[i+1].pose.position);
00540 }
00541 return length;
00542 }
00543
00544 void MoveBaseTopo::roadmapCB(msg::TopologicalRoadmap::ConstPtr roadmap)
00545 {
00546 Lock l(mutex_);
00547 roadmap_ = fromRosMessage(*roadmap);
00548
00549 removeBlockedEdges(blocked_edges_, roadmap_);
00550 ROS_DEBUG_NAMED("roadmap_cb", "Received roadmap with %zu nodes",
00551 roadmap->nodes.size());
00552 }
00553
00554
00555
00556 void MoveBaseTopo::localizationCB (const gm::PoseStamped& loc)
00557 {
00558 unsigned g;
00559 bool need_to_update;
00560 {
00561 Lock l(mutex_);
00562 g = tmap::frameGrid(loc.header.frame_id);
00563 need_to_update = (!current_grid_ || (g != *current_grid_));
00564 }
00565 if (need_to_update)
00566 {
00567 current_grid_ = g;
00568 nm::OccupancyGrid::ConstPtr grid = getGrid(g);
00569 Lock l(mutex_);
00570 grid_switch_ = true;
00571 costmap_.updateStaticMap(*grid);
00572 }
00573 }
00574
00575
00576 nm::OccupancyGrid::ConstPtr MoveBaseTopo::getGrid (const unsigned g) const
00577 {
00578 typedef wh::MessageWithMetadata<nm::OccupancyGrid>::ConstPtr Grid;
00579 vector<wh::Condition> conditions(1);
00580 conditions[0].field_name = "id";
00581 conditions[0].predicate = wh::Condition::EQUALS;
00582 conditions[0].args.push_back(boost::lexical_cast<string>(g));
00583 ros::Rate r(10);
00584 while (ros::ok())
00585 {
00586 const vector<Grid> results = grids_.pullAllResults(conditions);
00587 ROS_ASSERT_MSG (results.size()<2, "Unexpected case: there were "
00588 " multiple grids stored for id %u", g);
00589 if (results.size()==1)
00590 return results[0];
00591 ROS_WARN_THROTTLE (1.0, "Couldn't find grid %u in warehouse", g);
00592 r.sleep();
00593 }
00594
00595 return Grid();
00596 }
00597
00598
00599
00600
00601 void MoveBaseTopo::gridUpdateCB (const wh::UpdateNotification& m)
00602 {
00603 if (m.update_type == wh::UpdateNotification::UPDATE_METADATA)
00604 {
00605 const unsigned g = wh::getMetadataVal<int>(m.metadata, "id");
00606 bool need_to_update;
00607 {
00608 Lock l(mutex_);
00609 need_to_update = (current_grid_ && (g==*current_grid_));
00610 }
00611 if (need_to_update)
00612 {
00613 nm::OccupancyGrid::ConstPtr grid = getGrid(g);
00614 Lock l(mutex_);
00615 costmap_.updateStaticMap(*grid);
00616 }
00617 }
00618 }
00619
00620
00621
00622 };
00623
00624 int main(int argc, char** argv)
00625 {
00626 ros::init(argc, argv, "move_base_topo_node");
00627 topological_roadmap::MoveBaseTopo mb;
00628 ros::spin();
00629 return(0);
00630 }