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