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
00041 #include <topological_roadmap/roadmap.h>
00042 #include <topological_roadmap/ros_conversion.h>
00043 #include <graph_mapping_utils/ros.h>
00044 #include <graph_mapping_utils/to_string.h>
00045 #include <graph_mapping_utils/geometry.h>
00046 #include <occupancy_grid_utils/shortest_path.h>
00047 #include <topological_map_2d/ros_conversion.h>
00048 #include <warehouse/warehouse_client.h>
00049 #include <topological_nav_msgs/RoadmapPath.h>
00050 #include <ros/ros.h>
00051 #include <boost/foreach.hpp>
00052 #include <boost/thread.hpp>
00053 #include <boost/optional.hpp>
00054 #include <iostream>
00055 #include <sstream>
00056
00057 namespace topological_roadmap
00058 {
00059
00060 namespace gmu=graph_mapping_utils;
00061 namespace tmap=topological_map_2d;
00062 namespace msg=topological_nav_msgs;
00063 namespace gm=geometry_msgs;
00064 namespace wh=warehouse;
00065 namespace vm=visualization_msgs;
00066 namespace nm=nav_msgs;
00067 namespace gu=occupancy_grid_utils;
00068
00069 using gmu::toString;
00070 using std::string;
00071 using std::vector;
00072 using std::pair;
00073 using std::map;
00074 using boost::optional;
00075
00076 typedef boost::mutex::scoped_lock Lock;
00077 typedef std::set<unsigned> Nodes;
00078 typedef vector<gm::Point> PointVec;
00079
00080
00081
00082
00083
00084 class RoadmapNode
00085 {
00086 public:
00087 RoadmapNode();
00088
00089 private:
00090
00091
00092
00093
00094
00095
00096 void graphCB (const msg::TopologicalGraph& m);
00097
00098
00099 void locCB (const gm::PoseStamped& l);
00100
00101
00102 void gridUpdateCB (const wh::UpdateNotification& m);
00103
00104
00105 void pathCB (const msg::RoadmapPath& m);
00106
00107
00108
00109
00110
00111 nm::OccupancyGrid::ConstPtr getGrid (const unsigned g) const;
00112 PointVec potentialWaypoints () const;
00113
00114
00115
00116
00117
00118
00119 ros::NodeHandle param_nh_;
00120
00121
00122
00123 const double robot_radius_;
00124
00125
00126 const double waypoint_spacing_;
00127
00128
00129 const string vis_frame_;
00130
00131
00132 const bool visualize_node_ids_;
00133
00134
00135
00136
00137
00138
00139 tmap::TopologicalMap tmap_;
00140
00141
00142 Roadmap roadmap_;
00143
00144
00145 optional<gm::PoseStamped> last_loc_;
00146
00147
00148 optional<double> grid_size_;
00149
00150
00151 map<unsigned, ros::Time> grid_update_times_;
00152
00153
00154 map<unsigned, ros::Time> roadmap_update_times_;
00155
00156
00157 vector<unsigned> path_;
00158
00159
00160
00161
00162
00163
00164 boost::mutex mutex_;
00165
00166
00167 ros::NodeHandle nh_;
00168
00169
00170 wh::WarehouseClient db_;
00171
00172
00173 wh::Collection<nm::OccupancyGrid> grids_;
00174
00175
00176 tf::TransformListener tf_;
00177
00178
00179 ros::Timer vis_timer_;
00180
00181
00182 ros::Subscriber graph_sub_;
00183
00184
00185 ros::Subscriber loc_sub_;
00186
00187
00188 ros::Subscriber grid_sub_;
00189
00190
00191 ros::Subscriber path_sub_;
00192
00193
00194 ros::Publisher vis_pub_;
00195
00196
00197 ros::Publisher roadmap_pub_;
00198
00199
00200 ros::Publisher inflated_grid_pub_;
00201 };
00202
00203
00204
00205
00206
00207 RoadmapNode::RoadmapNode () :
00208
00209 param_nh_("~"),
00210 robot_radius_(gmu::getParam<double>(param_nh_, "robot_radius")),
00211 waypoint_spacing_(gmu::getParam<double>(param_nh_, "waypoint_spacing")),
00212 vis_frame_(gmu::getParam<string>(param_nh_, "visualization_frame", "map")),
00213 visualize_node_ids_(gmu::getParam<bool>(param_nh_, "visualize_node_ids", false)),
00214
00215
00216 db_("topological_navigation"),
00217 grids_(db_.setupCollection<nm::OccupancyGrid>("grids")),
00218 graph_sub_(nh_.subscribe("topological_graph", 1, &RoadmapNode::graphCB,
00219 this)),
00220 loc_sub_(nh_.subscribe("topological_localization", 5, &RoadmapNode::locCB,
00221 this)),
00222 grid_sub_(nh_.subscribe("warehouse/topological_navigation/grids/notify",
00223 10000, &RoadmapNode::gridUpdateCB, this)),
00224 path_sub_(nh_.subscribe("roadmap_path", 5, &RoadmapNode::pathCB, this)),
00225 vis_pub_(nh_.advertise<vm::Marker>("visualization_marker", 10)),
00226 roadmap_pub_(nh_.advertise<msg::TopologicalRoadmap>("topological_roadmap", 10)),
00227 inflated_grid_pub_(nh_.advertise<nm::OccupancyGrid>("inflated_grid", 10))
00228
00229 {
00230 ROS_DEBUG_STREAM_NAMED ("init", "Roadmap builder initialized");
00231 }
00232
00233
00234
00235
00236
00237
00238
00239 optional<gm::Point> freePointNear (const nm::OccupancyGrid& grid,
00240 const double x0, const double y0,
00241 const double r)
00242 {
00243 const nm::MapMetaData& geom=grid.info;
00244 const int cell_radius = floor(r/geom.resolution);
00245 gu::Cell center = gu::pointCell(geom, gmu::makePoint(x0, y0));
00246 optional<gm::Point> p;
00247 for (int dx=0; dx<=cell_radius; dx++)
00248 {
00249 for (int dy=0; dy<=cell_radius; dy++)
00250 {
00251 for (int sx=-1; sx<=1; sx+=2)
00252 {
00253 for (int sy=-1; sy<=1; sy+=2)
00254 {
00255 const gu::Cell c(center.x+dx*sx, center.y+dy*sy);
00256 if (grid.data[gu::cellIndex(geom, c)]==gu::UNOCCUPIED)
00257 return optional<gm::Point>(gu::cellCenter(geom, c));
00258 }
00259 }
00260 }
00261 }
00262 return optional<gm::Point>();
00263 }
00264
00265 nm::OccupancyGrid::ConstPtr RoadmapNode::getGrid (const unsigned g) const
00266 {
00267 typedef wh::MessageWithMetadata<nm::OccupancyGrid>::ConstPtr Grid;
00268 vector<wh::Condition> conditions(1);
00269 conditions[0].field_name = "id";
00270 conditions[0].predicate = wh::Condition::EQUALS;
00271 conditions[0].args.push_back(boost::lexical_cast<string>(g));
00272 vector<Grid> results = grids_.pullAllResults(conditions);
00273 if (results.size()>0)
00274 return results[0];
00275 else
00276 return nm::OccupancyGrid::ConstPtr();
00277 }
00278
00279 PointVec RoadmapNode::potentialWaypoints () const
00280 {
00281 PointVec points;
00282 const double r=*grid_size_/2.0;
00283 for (double x=-r+waypoint_spacing_/2.0; x<=r;
00284 x+=waypoint_spacing_)
00285 {
00286 for (double y=-r+waypoint_spacing_/2.0; y<=r;
00287 y+=waypoint_spacing_)
00288 {
00289 points.push_back(gmu::makePoint(x,y));
00290 }
00291 }
00292 return points;
00293 }
00294
00295
00296 void RoadmapNode::graphCB (const msg::TopologicalGraph& m)
00297 {
00298 ROS_DEBUG_STREAM_NAMED ("graph_cb", "Entering graph callback");
00299 Lock l(mutex_);
00300 tmap_ = tmap::fromMessage(m);
00301 BOOST_FOREACH (const tmap::GraphVertex& v, vertices(tmap_))
00302 {
00303 if (grid_size_)
00304 ROS_ASSERT_MSG(*grid_size_==tmap_[v].x_size &&
00305 *grid_size_==tmap_[v].y_size,
00306 "Assumption that all grids are identical squares failed.");
00307 else
00308 grid_size_ = tmap_[v].x_size;
00309 const unsigned g = tmap_[v].id;
00310
00311
00312 if (grid_update_times_[g] > roadmap_update_times_[g])
00313 {
00314 ROS_DEBUG_STREAM_NAMED ("graph_cb", "Updating grid " << g);
00315 roadmap_update_times_[g] = ros::Time::now();
00316
00317
00318 nm::OccupancyGrid::ConstPtr grid = getGrid(g);
00319 if (!grid)
00320 {
00321 ROS_WARN ("Skipping grid %u as it's not in the db yet", g);
00322 continue;
00323 }
00324 ROS_DEBUG_STREAM_NAMED ("graph_cb", "Loaded grid");
00325
00326 {
00327
00328
00329
00330 nm::OccupancyGrid::ConstPtr inflated =
00331 gu::inflateObstacles(*grid, 2*robot_radius_);
00332 ROS_DEBUG_STREAM_NAMED ("graph_cb", "Inflated obstacles");
00333
00334 const PointVec waypoints = nodesOnGrid(g, roadmap_, tmap_).second;
00335
00336
00337 BOOST_FOREACH (const gm::Point w, potentialWaypoints())
00338 {
00339
00340
00341 bool covered = false;
00342 BOOST_FOREACH (const gm::Point p, waypoints)
00343 {
00344 if (gmu::euclideanDistance(w,p)<waypoint_spacing_/2.0)
00345 {
00346 covered=true;
00347 break;
00348 }
00349 }
00350 if (covered) continue;
00351
00352
00353 optional<gm::Point> pt = freePointNear(*inflated, w.x, w.y,
00354 waypoint_spacing_/4.0);
00355 if (pt)
00356 {
00357 msg::RoadmapNode info;
00358 info.grid = g;
00359 info.position = *pt;
00360 const unsigned id = roadmap_.addNode(info);
00361 ROS_DEBUG_STREAM_NAMED ("update", "Added node " << id <<
00362 " on grid " << g << " at " << toString(*pt));
00363 }
00364 else
00365 {
00366 ROS_DEBUG_NAMED ("update", "Couldn't find free cell near (%.2f, %.2f)"
00367 " so not adding roadmap node", w.x, w.y);
00368 }
00369 }
00370 }
00371
00372
00373
00374 nm::OccupancyGrid::ConstPtr inflated2 =
00375 gu::inflateObstacles(*grid, robot_radius_, true);
00376 inflated_grid_pub_.publish(inflated2);
00377
00378
00379
00380 const pair<vector<unsigned>, PointVec> updated_waypoints =
00381 nodesOnGrid(g, roadmap_, tmap_);
00382 for (unsigned i=0; i<updated_waypoints.first.size(); i++)
00383 {
00384 const unsigned n=updated_waypoints.first[i];
00385 const gm::Point pos = positionOnGrid(n, g, roadmap_, tmap_);
00386 const gu::Cell c = gu::pointCell(grid->info, pos);
00387 const double max_dist = 2.0*waypoint_spacing_/grid->info.resolution;
00388 gu::TerminationCondition term(max_dist);
00389 ROS_DEBUG_STREAM_NAMED ("shortest_path", "Looking for paths from "
00390 << n << " with max length " <<
00391 2*waypoint_spacing_);
00392 gu::ResultPtr res = gu::singleSourceShortestPaths(*inflated2, c,
00393 term);
00394 for (unsigned j=0; j<updated_waypoints.first.size(); j++)
00395 {
00396 const unsigned n2=updated_waypoints.first[j];
00397 if (n<=n2)
00398 continue;
00399 const GraphVertex v = roadmap_.node(n);
00400 const GraphVertex v2 = roadmap_.node(n2);
00401 const gm::Point pos = positionOnGrid(n2, g, roadmap_, tmap_);
00402
00403 const gu::Cell c2 = gu::pointCell(grid->info, pos);
00404 optional<double> d = gu::distance(res, c2);
00405 if (d)
00406 {
00407 msg::RoadmapEdge info;
00408 info.id = 0;
00409 info.grid = g;
00410 info.src = n;
00411 info.dest = n2;
00412 info.cost = *d*grid->info.resolution;
00413 ROS_DEBUG_STREAM_NAMED ("shortest_path", "Path of length " <<
00414 info.cost << " from " << n << " to " <<
00415 n2 << " on " << g);
00416
00417 pair<GraphEdge, bool> res = edge(v, v2, roadmap_);
00418 if (res.second) {
00419 msg::RoadmapEdge& existing = roadmap_[res.first];
00420 ROS_ASSERT_MSG(existing.src == info.src &&
00421 existing.dest == info.dest,
00422 "Edge (%u, %u) didn't match (%u, %u)",
00423 existing.src, existing.dest, info.src, info.dest);
00424 existing.cost = info.cost;
00425 ROS_DEBUG_STREAM_NAMED ("update", "Updating edge cost from "
00426 << n << " to " << n2 << " to " <<
00427 info.cost);
00428 }
00429 else
00430 roadmap_.addEdge(info);
00431 }
00432 }
00433 }
00434 }
00435 }
00436
00437
00438 visualize(roadmap_, vis_pub_, tf_, vis_frame_, visualize_node_ids_, path_);
00439 roadmap_pub_.publish(toRosMessage(roadmap_));
00440
00441 ROS_DEBUG_STREAM_NAMED ("graph_cb", "Leaving graph callback");
00442 }
00443
00444
00445
00446
00447
00448
00449 void RoadmapNode::locCB (const gm::PoseStamped& l)
00450 {
00451 ROS_DEBUG_STREAM_NAMED ("loc_cb", "Entering localization callback");
00452 Lock lock(mutex_);
00453 if (!last_loc_ || last_loc_->header.frame_id!=l.header.frame_id)
00454 ROS_DEBUG_STREAM_NAMED ("loc_cb", "New local frame " << l.header.frame_id);
00455 last_loc_ = l;
00456 ROS_DEBUG_STREAM_NAMED ("loc_cb", "Leaving localization callback");
00457 }
00458
00459
00460
00461
00462
00463
00464
00465
00466 unsigned notificationGrid (const wh::UpdateNotification& m)
00467 {
00468 if (m.update_type != wh::UpdateNotification::UPDATE_METADATA)
00469 return 0;
00470 std::stringstream s(m.metadata, std::ios_base::in);
00471 YAML::Parser parser(s);
00472 YAML::Node doc;
00473 const bool success = parser.GetNextDocument(doc);
00474 ROS_ASSERT_MSG(success, "Unknown error parsing metadata %s",
00475 m.metadata.c_str());
00476 if (const YAML::Node* p_name = doc.FindValue("id"))
00477 {
00478 string val;
00479 *p_name >> val;
00480 return atoi(val.c_str());
00481 }
00482 else {
00483 ROS_WARN_STREAM ("Didn't find id key in " << m.metadata);
00484 return 0;
00485 }
00486 }
00487
00488 void RoadmapNode::gridUpdateCB (const wh::UpdateNotification& m)
00489 {
00490
00491 const unsigned g = notificationGrid(m);
00492
00493
00494 if (g==0)
00495 return;
00496
00497 Lock l(mutex_);
00498 grid_update_times_[g] = ros::Time::now();
00499 }
00500
00501 void RoadmapNode::pathCB (const msg::RoadmapPath& m)
00502 {
00503 Lock l(mutex_);
00504 path_ = m.path;
00505 }
00506
00507 }
00508
00509 int main (int argc, char** argv)
00510 {
00511 ros::init(argc, argv, "roadmap_builder");
00512 topological_roadmap::RoadmapNode node;
00513 ros::spin();
00514 return 0;
00515 }