Go to the documentation of this file.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
00040 #ifndef TOPOLOGICAL_MAP_2D_TOPOLOGICAL_MAP_H
00041 #define TOPOLOGICAL_MAP_2D_TOPOLOGICAL_MAP_H
00042
00043 #include <topological_nav_msgs/TopologicalMapNode.h>
00044 #include <topological_nav_msgs/TopologicalMapEdge.h>
00045 #include <map>
00046
00047 #define BOOST_NO_HASH
00048 #include <boost/graph/adjacency_list.hpp>
00049 #include <boost/graph/graph_traits.hpp>
00050
00051 namespace topological_map_2d
00052 {
00053
00054 namespace msg=topological_nav_msgs;
00055
00056 typedef boost::adjacency_list<boost::listS, boost::listS, boost::undirectedS,
00057 msg::TopologicalMapNode,
00058 msg::TopologicalMapEdge> Graph;
00059 typedef boost::graph_traits<Graph>::edge_descriptor GraphEdge;
00060 typedef boost::graph_traits<Graph>::vertex_descriptor GraphVertex;
00061
00062
00070 class TopologicalMap : public Graph
00071 {
00072 public:
00073
00074 typedef msg::TopologicalMapNode Node;
00075 typedef msg::TopologicalMapEdge Edge;
00076
00078 TopologicalMap ();
00079
00081 TopologicalMap (const TopologicalMap& g);
00082
00084 TopologicalMap& operator= (const TopologicalMap& g);
00085
00088 GraphVertex node (unsigned id) const;
00089
00092 GraphEdge edge (unsigned id) const;
00093
00096 Node& nodeInfo (unsigned id);
00097
00100 Edge& edgeInfo (unsigned id);
00101
00104 const Node& nodeInfo (unsigned id) const;
00105
00108 const Edge& edgeInfo (unsigned id) const;
00109
00114 GraphVertex addNode (const Node& info);
00115
00121 GraphEdge addEdge (const Edge& info);
00122
00126 void removeNode (unsigned id);
00127
00131 void removeEdge (unsigned id);
00132
00133 private:
00134
00136 void recomputeIndices ();
00137
00138 std::map<unsigned, GraphVertex> vertex_map_;
00139 std::map<unsigned, GraphEdge> edge_map_;
00140
00141 };
00142
00144 std::string gridFrame (const unsigned g);
00145
00148 unsigned frameGrid (const std::string& frame);
00149
00150 }
00151
00152 #endif // include guard