Classes | Typedefs | Functions
topological_roadmap Namespace Reference

Classes

struct  BlockedEdge
struct  DuplicateEdgeIdException
 Exception for trying to add an EdgeId that already exists. More...
struct  DuplicateNodeIdException
 Exception for trying to add a NodeId that already exists. More...
class  MoveBaseTopo
struct  ParallelEdgeException
 Exception when trying to add edge between two already connected nodes. More...
class  Roadmap
class  RoadmapException
class  RoadmapNode
struct  SingleSourceShortestPaths
struct  UnknownEdgeIdException
 Exception for unknown EdgeId. More...
struct  UnknownNodeIdException
 Exception for unknown node id. More...

Typedefs

typedef pair< DistanceMap,
PredMap
DijkstraResult
typedef map< GraphVertex, double > DistanceMap
typedef std::map< unsigned,
GraphEdge
EdgeMap
typedef std::vector< unsigned > EdgeVec
typedef boost::adjacency_list
< boost::multisetS,
boost::listS,
boost::undirectedS,
msg::RoadmapNode,
msg::RoadmapEdge > 
Graph
typedef boost::graph_traits
< Graph >::edge_descriptor 
GraphEdge
typedef boost::graph_traits
< Graph >::vertex_descriptor 
GraphVertex
typedef vector< unsigned > Grids
typedef boost::mutex::scoped_lock Lock
typedef vector< unsigned > Nodes
typedef std::vector< unsigned > NodeVec
typedef std::pair< NodeVec,
EdgeVec
Path
typedef vector< gm::PointPointVec
typedef map< GraphVertex,
GraphVertex
PredMap
typedef boost::shared_ptr
< SingleSourceShortestPaths
ResultPtr
typedef std::map< unsigned,
GraphVertex
VertexMap
typedef std::vector< unsigned > WaypointVec

Functions

DijkstraResult dijkstra (const Roadmap &r, const unsigned src)
boost::optional< PathextractPath (ResultPtr res, unsigned dest)
 Extract path from shortest path query, or null value if there's no path.
optional< PathextractPath (DijkstraResult &res, const unsigned src, const unsigned dest, const Roadmap &r)
optional< gm::PointfreePointNear (const nm::OccupancyGrid &grid, const double x0, const double y0, const double r)
Roadmap fromRosMessage (const msg::TopologicalRoadmap &r)
 Convert TopologicalRoadmapROS message back into ROS.
gm::Point nodePos (const Roadmap &r, tf::TransformListener &tf, const std::string &frame, const unsigned n)
std::pair< std::vector
< unsigned >, std::vector
< geometry_msgs::Point > > 
nodesOnGrid (const unsigned g, const Roadmap &r, const topological_map_2d::TopologicalMap &t)
geometry_msgs::Point positionOnGrid (unsigned n, unsigned g, const Roadmap &r, const topological_map_2d::TopologicalMap &t)
ResultPtr shortestPaths (const Roadmap &r, unsigned src)
 Return object that can be used for shortest path queries Note the code scales with the largest node id in the graph, and assumes all edge costs are positive.
msg::TopologicalRoadmap::Ptr toRosMessage (const Roadmap &r)
 Convert Roadmap into TopologicalRoadmap ROS message.
void visualize (const Roadmap &r, ros::Publisher &pub, tf::TransformListener &tf, const std::string &frame, bool use_node_ids, const std::vector< unsigned > &path)
void visualize (const Roadmap &r, ros::Publisher &pub, tf::TransformListener &tf, const std::string &frame, const bool use_node_ids, const Path &path)
void visualizeEdges (const Roadmap &r, ros::Publisher &pub, tf::TransformListener &tf, const std::string &frame, const Path &plan)
void visualizeNodes (const Roadmap &r, ros::Publisher &pub, tf::TransformListener &tf, const std::string &frame, const bool use_node_ids)

Typedef Documentation

Definition at line 60 of file shortest_paths.cpp.

Definition at line 58 of file shortest_paths.cpp.

typedef std::map<unsigned, GraphEdge> topological_roadmap::EdgeMap

Definition at line 58 of file roadmap.cpp.

typedef std::vector<unsigned> topological_roadmap::EdgeVec

Definition at line 51 of file shortest_paths.h.

typedef boost::adjacency_list<boost::multisetS, boost::listS, boost::undirectedS, msg::RoadmapNode, msg::RoadmapEdge> topological_roadmap::Graph

Definition at line 56 of file roadmap.h.

typedef boost::graph_traits<Graph>::edge_descriptor topological_roadmap::GraphEdge

Definition at line 57 of file roadmap.h.

typedef boost::graph_traits<Graph>::vertex_descriptor topological_roadmap::GraphVertex

Definition at line 58 of file roadmap.h.

typedef vector<unsigned> topological_roadmap::Grids

Definition at line 61 of file roadmap.cpp.

typedef boost::mutex::scoped_lock topological_roadmap::Lock

Definition at line 63 of file move_base_topo.cpp.

typedef std::set< unsigned > topological_roadmap::Nodes

Definition at line 60 of file roadmap.cpp.

typedef std::vector<unsigned> topological_roadmap::NodeVec

Definition at line 50 of file shortest_paths.h.

typedef std::vector< unsigned > topological_roadmap::Path

Definition at line 52 of file shortest_paths.h.

Definition at line 59 of file roadmap.cpp.

Definition at line 59 of file shortest_paths.cpp.

Definition at line 47 of file shortest_paths.h.

typedef std::map<unsigned, GraphVertex> topological_roadmap::VertexMap

Definition at line 57 of file roadmap.cpp.

typedef std::vector<unsigned> topological_roadmap::WaypointVec

Definition at line 71 of file move_base_topo.h.


Function Documentation

DijkstraResult topological_roadmap::dijkstra ( const Roadmap &  r,
const unsigned  src 
)

Definition at line 62 of file shortest_paths.cpp.

optional< Path > topological_roadmap::extractPath ( ResultPtr  res,
unsigned  dest 
)

Extract path from shortest path query, or null value if there's no path.

Definition at line 156 of file shortest_paths.cpp.

optional<Path> topological_roadmap::extractPath ( DijkstraResult &  res,
const unsigned  src,
const unsigned  dest,
const Roadmap &  r 
)

Definition at line 128 of file shortest_paths.cpp.

optional<gm::Point> topological_roadmap::freePointNear ( const nm::OccupancyGrid &  grid,
const double  x0,
const double  y0,
const double  r 
)

Definition at line 236 of file roadmap_builder.cpp.

Roadmap topological_roadmap::fromRosMessage ( const msg::TopologicalRoadmap &  r)

Convert TopologicalRoadmapROS message back into ROS.

Definition at line 68 of file ros_conversion.cpp.

gm::Point topological_roadmap::nodePos ( const Roadmap &  r,
tf::TransformListener tf,
const std::string &  frame,
const unsigned  n 
)

Definition at line 82 of file ros_conversion.cpp.

pair< Nodes, PointVec > topological_roadmap::nodesOnGrid ( const unsigned  g,
const Roadmap &  r,
const topological_map_2d::TopologicalMap t 
)
Return values:
Allwaypoints lying on a given grid of the topological map

Definition at line 221 of file roadmap.cpp.

gm::Point topological_roadmap::positionOnGrid ( unsigned  n,
unsigned  g,
const Roadmap &  r,
const topological_map_2d::TopologicalMap t 
)
Return values:
Positionof a waypoint wrt a grid on the topological map

Definition at line 197 of file roadmap.cpp.

ResultPtr topological_roadmap::shortestPaths ( const Roadmap &  r,
unsigned  src 
)

Return object that can be used for shortest path queries Note the code scales with the largest node id in the graph, and assumes all edge costs are positive.

Definition at line 122 of file shortest_paths.cpp.

msg::TopologicalRoadmap::Ptr topological_roadmap::toRosMessage ( const Roadmap &  r)

Convert Roadmap into TopologicalRoadmap ROS message.

Definition at line 55 of file ros_conversion.cpp.

void topological_roadmap::visualize ( const Roadmap &  r,
ros::Publisher pub,
tf::TransformListener tf,
const std::string &  frame,
bool  use_node_ids,
const std::vector< unsigned > &  path 
)

Visualize roadmap r using pub, which must be a publisher of VisualizationMarker messages.

Parameters:
frameFrame to transform data into before publishing.
use_node_idsIf true, each node will be a separate marker with the corresponding node's id, to facilitate debugging. If false, the entire roadmap will be published as a single marker.
void topological_roadmap::visualize ( const Roadmap &  r,
ros::Publisher pub,
tf::TransformListener tf,
const std::string &  frame,
const bool  use_node_ids,
const Path path 
)

Definition at line 204 of file ros_conversion.cpp.

void topological_roadmap::visualizeEdges ( const Roadmap &  r,
ros::Publisher pub,
tf::TransformListener tf,
const std::string &  frame,
const Path plan 
)

Definition at line 142 of file ros_conversion.cpp.

void topological_roadmap::visualizeNodes ( const Roadmap &  r,
ros::Publisher pub,
tf::TransformListener tf,
const std::string &  frame,
const bool  use_node_ids 
)

Definition at line 94 of file ros_conversion.cpp.



topological_roadmap
Author(s): Bhaskara Marthi
autogenerated on Sun Jan 5 2014 11:39:33