Go to the documentation of this file.00001
00026 #ifndef _TOPOLOGICAL_MAP_H_
00027 #define _TOPOLOGICAL_MAP_H_
00028
00029 #include <topological_tools/topological_node.h>
00030
00031
00032
00033 namespace topological_tools
00034 {
00035 class TopologicalMap
00036 {
00037 public:
00038 TopologicalMap ( const std::string& map_file );
00039
00040 bool hasNode ( const std::string& node_name );
00041
00042 boost::shared_ptr<TopologicalNode> getNodeByName ( const std::string& node_name );
00043
00044 void addNode ( geometry_msgs::Pose goal, const std::string& node_name );
00045
00046 private :
00047
00048 std::map<std::string, boost::shared_ptr<TopologicalNode> > node_map_;
00049 };
00050 }
00051
00052 #endif