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
00039 #include <topological_roadmap/roadmap.h>
00040 #include <topological_roadmap/exception.h>
00041 #include <graph_mapping_utils/general.h>
00042 #include <graph_mapping_utils/geometry.h>
00043 #include <graph_mapping_utils/to_string.h>
00044 #include <boost/foreach.hpp>
00045
00046 namespace topological_roadmap
00047 {
00048
00049 namespace gmu=graph_mapping_utils;
00050 namespace msg=topological_nav_msgs;
00051 namespace tmap=topological_map_2d;
00052 namespace gm=geometry_msgs;
00053
00054 using std::vector;
00055 using std::pair;
00056
00057 typedef std::map<unsigned, GraphVertex> VertexMap;
00058 typedef std::map<unsigned, GraphEdge> EdgeMap;
00059 typedef vector<gm::Point> PointVec;
00060 typedef vector<unsigned> Nodes;
00061 typedef vector<unsigned> Grids;
00062
00063
00064
00065
00066
00067
00068 Roadmap::Roadmap () : Graph(), next_node_id_(1), next_edge_id_(1)
00069 {}
00070
00071
00072 Roadmap::Roadmap (const Roadmap& r) :
00073 Graph(r), next_node_id_(r.next_node_id_), next_edge_id_(r.next_edge_id_)
00074 {
00075 recomputeIndexes();
00076 }
00077
00078 Roadmap& Roadmap::operator= (const Roadmap& r)
00079 {
00080 Graph::operator=(r);
00081 next_node_id_ = r.next_node_id_;
00082 next_edge_id_ = r.next_edge_id_;
00083 recomputeIndexes();
00084 return *this;
00085 }
00086
00087 void Roadmap::recomputeIndexes ()
00088 {
00089 vertex_map_.clear();
00090 edge_map_.clear();
00091 grid_nodes_.clear();
00092 BOOST_FOREACH (const GraphVertex& v, vertices(*this))
00093 {
00094 const NodeInfo& info = operator[](v);
00095 vertex_map_[info.id] = v;
00096
00097
00098 grid_nodes_[info.grid].insert(info.id);
00099 }
00100 BOOST_FOREACH (const GraphEdge& e, edges(*this))
00101 edge_map_[operator[](e).id] = e;
00102 }
00103
00104
00105
00106
00107
00108 GraphVertex Roadmap::node (unsigned id) const
00109 {
00110 VertexMap::const_iterator pos = vertex_map_.find(id);
00111 if (pos==vertex_map_.end())
00112 throw UnknownNodeIdException(id);
00113 return pos->second;
00114 }
00115
00116 GraphEdge Roadmap::edge (unsigned id) const
00117 {
00118 EdgeMap::const_iterator pos = edge_map_.find(id);
00119 if (pos==edge_map_.end())
00120 throw UnknownEdgeIdException(id);
00121 return pos->second;
00122 }
00123
00124 const Roadmap::NodeInfo& Roadmap::nodeInfo (const unsigned i) const
00125 {
00126 return operator[](node(i));
00127 }
00128
00129 const Roadmap::EdgeInfo& Roadmap::edgeInfo (const unsigned i) const
00130 {
00131 return operator[](edge(i));
00132 }
00133
00134 Roadmap::Nodes Roadmap::gridNodes (const unsigned g) const
00135 {
00136 if (gmu::contains(grid_nodes_, g))
00137 return gmu::keyValue(grid_nodes_, g);
00138 else
00139 return Nodes();
00140 }
00141
00142
00143
00144
00145
00146 unsigned Roadmap::addNode (const NodeInfo& info_orig)
00147 {
00148 NodeInfo info = info_orig;
00149 if (info.id == 0)
00150 {
00151 while (gmu::contains(vertex_map_, next_node_id_))
00152 next_node_id_++;
00153 info.id = next_node_id_++;
00154 }
00155 if (gmu::contains(vertex_map_, info.id))
00156 throw DuplicateNodeIdException(info.id);
00157 vertex_map_[info.id] = add_vertex(info, *this);
00158
00159
00160 grid_nodes_[info.grid].insert(info.id);
00161
00162 return info.id;
00163 }
00164
00165 unsigned Roadmap::addEdge (const EdgeInfo& info_orig)
00166 {
00167 EdgeInfo info = info_orig;
00168 if (info.id == 0)
00169 {
00170 while (gmu::contains(edge_map_, next_edge_id_))
00171 next_edge_id_++;
00172 info.id = next_edge_id_++;
00173 }
00174 if (gmu::contains(edge_map_, info.id))
00175 throw DuplicateEdgeIdException(info.id);
00176
00177 const GraphVertex v1 = node(info.src);
00178 const GraphVertex v2 = node(info.dest);
00179 std::pair<GraphEdge, bool> res = add_edge(v1, v2, info, *this);
00180 if (!res.second)
00181 throw ParallelEdgeException(info.src, info.dest);
00182 edge_map_[info.id] = res.first;
00183 return info.id;
00184 }
00185
00186 void Roadmap::deleteEdge (const unsigned id)
00187 {
00188 boost::remove_edge(edge(id), *this);
00189 edge_map_.erase(id);
00190 }
00191
00192
00193
00194
00195
00196
00197 gm::Point positionOnGrid (const unsigned n, const unsigned g, const Roadmap& r,
00198 const tmap::TopologicalMap& tmap)
00199 {
00200 const msg::RoadmapNode& info = r.nodeInfo(n);
00201 const unsigned g2 = info.grid;
00202 if (g2==g)
00203 {
00204 return info.position;
00205 }
00206 else
00207 {
00208 const tmap::GraphVertex v = tmap.node(g);
00209 const tmap::GraphVertex v2 = tmap.node(g2);
00210 pair<tmap::GraphEdge, bool> res = edge(v, v2, tmap);
00211 ROS_ASSERT_MSG (res.second, "No edge between grid %u and grid %u "
00212 "containing %u", g, g2, n);
00213 const bool flip = (tmap[res.first].dest == g);
00214 const tf::Pose offset = gmu::toPose(tmap[res.first].offset);
00215 const tf::Transform tr = flip ? offset.inverse() : offset;
00216 return gmu::transformPoint(tr, info.position);
00217 }
00218 }
00219
00220 pair<Nodes, PointVec>
00221 nodesOnGrid (const unsigned g, const Roadmap& r,
00222 const tmap::TopologicalMap& tmap)
00223 {
00224 pair<Nodes, PointVec> res;
00225
00226
00227 BOOST_FOREACH (const unsigned n, r.gridNodes(g))
00228 {
00229 res.first.push_back(n);
00230 res.second.push_back(r.nodeInfo(n).position);
00231 }
00232
00233 const double x_size = tmap.nodeInfo(g).x_size;
00234 const double y_size = tmap.nodeInfo(g).y_size;
00235
00236
00237 BOOST_FOREACH (const tmap::GraphEdge e,
00238 out_edges(tmap.node(g), tmap))
00239 {
00240 const bool flip = (tmap[e].dest == g);
00241 const tf::Pose offset = gmu::toPose(tmap[e].offset);
00242 const tf::Transform tr = flip ? offset.inverse() : offset;
00243 const unsigned g2 = flip ? tmap[e].src : tmap[e].dest;
00244
00245
00246 BOOST_FOREACH (const unsigned n, r.gridNodes(g2))
00247 {
00248 ROS_ASSERT(g2==r.nodeInfo(n).grid);
00249 const gm::Point& pos = r.nodeInfo(n).position;
00250 const gm::Point local_pos = gmu::transformPoint(tr, pos);
00251
00252
00253 ROS_DEBUG_STREAM_NAMED ("nodes_on_grid", "Node " << n << " position on " << g2 << " is "
00254 << gmu::toString(pos) << " and on " << g <<
00255 " is " << gmu::toString(local_pos));
00256
00257 if (fabs(local_pos.x) < x_size/2 && fabs(local_pos.y) < y_size/2)
00258 {
00259 ROS_DEBUG_NAMED ("nodes_on_grid", "On grid");
00260 res.first.push_back(n);
00261 res.second.push_back(local_pos);
00262 }
00263 }
00264 }
00265
00266 return res;
00267
00268 }
00269
00270
00271
00272 }