#include <roadmap.h>
Public Types | |
typedef msg::RoadmapEdge | EdgeInfo |
typedef msg::RoadmapNode | NodeInfo |
typedef std::set< unsigned > | Nodes |
Public Member Functions | |
unsigned | addEdge (const EdgeInfo &info) |
Add an edge. If the id field of the info is 0, it is filled in by this function. | |
unsigned | addNode (const NodeInfo &info) |
Add a node. If the id of the info field is 0, it is filled in by this function. | |
void | deleteEdge (unsigned id) |
Delete an edge. | |
GraphEdge | edge (unsigned id) const |
Get edge descriptor for id. | |
const EdgeInfo & | edgeInfo (unsigned id) const |
Convenience function to get edge info. | |
Nodes | gridNodes (const unsigned g) const |
GraphVertex | node (unsigned id) const |
Get node descriptor for id. | |
const NodeInfo & | nodeInfo (unsigned id) const |
Convenience function to get node info. | |
Roadmap & | operator= (const Roadmap &r) |
Assignment. | |
void | recomputeIndexes () |
Recompute indexing info from the underlying graph. | |
Roadmap () | |
Default constructor creates empty graph. | |
Roadmap (const Roadmap &r) | |
Copy constructor. | |
Private Attributes | |
std::map< unsigned, GraphEdge > | edge_map_ |
std::map< unsigned, Nodes > | grid_nodes_ |
unsigned | next_edge_id_ |
unsigned | next_node_id_ |
std::map< unsigned, GraphVertex > | vertex_map_ |
A topological roadmap is overlaid over a topological_map_2d::TopologicalMap and used for navigation. Each roadmap node is a navigation waypoint and refers to some specific position in one of the local grids of the topological map. Each edge represents a navigable path between two waypoints on the same grid. Apart from the grid wrt which it is defined, each waypoint may also be on other grids, and this is what allows navigating across grids.
The class inherits from boost::adjacency_list with some additional indexing information that allows nodes and edges to be referred to using integer ids rather than boost graph descriptors. To maintain this information, all modifying operations on the graph should use {add,remove}{Node,Edge} rather than boost::add_vertex, etc. For other ops use the boost::adjacency_list ops, though some are wrapped for convenience, e.g., node/edgeInfo.
typedef msg::RoadmapEdge topological_roadmap::Roadmap::EdgeInfo |
typedef msg::RoadmapNode topological_roadmap::Roadmap::NodeInfo |
typedef std::set<unsigned> topological_roadmap::Roadmap::Nodes |
Default constructor creates empty graph.
Definition at line 68 of file roadmap.cpp.
topological_roadmap::Roadmap::Roadmap | ( | const Roadmap & | r | ) |
Copy constructor.
Definition at line 72 of file roadmap.cpp.
unsigned topological_roadmap::Roadmap::addEdge | ( | const EdgeInfo & | info | ) |
Add an edge. If the id field of the info is 0, it is filled in by this function.
Id | of newly added edge. |
UnknownNodeIdException | |
DuplicateEdgeIdException |
Definition at line 165 of file roadmap.cpp.
unsigned topological_roadmap::Roadmap::addNode | ( | const NodeInfo & | info | ) |
Add a node. If the id of the info field is 0, it is filled in by this function.
Id | of newly added node. |
Definition at line 146 of file roadmap.cpp.
void topological_roadmap::Roadmap::deleteEdge | ( | unsigned | id | ) |
Delete an edge.
UnknownEdgeIdException |
Definition at line 186 of file roadmap.cpp.
GraphEdge topological_roadmap::Roadmap::edge | ( | unsigned | id | ) | const |
Get edge descriptor for id.
UnknownEdgeIdException |
Definition at line 116 of file roadmap.cpp.
const Roadmap::EdgeInfo & topological_roadmap::Roadmap::edgeInfo | ( | unsigned | id | ) | const |
Convenience function to get edge info.
UnknownEdgeIdException |
Definition at line 129 of file roadmap.cpp.
Roadmap::Nodes topological_roadmap::Roadmap::gridNodes | ( | const unsigned | g | ) | const |
Set | of nodes defined wrt this grid. If this grid has never been mentioned by any node, will just return the empty set. |
Definition at line 134 of file roadmap.cpp.
GraphVertex topological_roadmap::Roadmap::node | ( | unsigned | id | ) | const |
Get node descriptor for id.
UnknownNodeIdException |
Definition at line 108 of file roadmap.cpp.
const Roadmap::NodeInfo & topological_roadmap::Roadmap::nodeInfo | ( | unsigned | id | ) | const |
Convenience function to get node info.
UnknownNodeIdException |
Definition at line 124 of file roadmap.cpp.
Assignment.
Definition at line 78 of file roadmap.cpp.
Recompute indexing info from the underlying graph.
Definition at line 87 of file roadmap.cpp.
std::map<unsigned, GraphEdge> topological_roadmap::Roadmap::edge_map_ [private] |
std::map<unsigned, Nodes> topological_roadmap::Roadmap::grid_nodes_ [private] |
unsigned topological_roadmap::Roadmap::next_edge_id_ [private] |
unsigned topological_roadmap::Roadmap::next_node_id_ [private] |
std::map<unsigned, GraphVertex> topological_roadmap::Roadmap::vertex_map_ [private] |