Classes | Typedefs | Functions
rtabmap::graph Namespace Reference

Classes

class  G2OOptimizer
class  Node
class  Optimizer
struct  Order
class  TOROOptimizer

Typedefs

typedef std::pair< int, float > Pair

Functions

std::list< std::pair< int,
Transform > > RTABMAP_EXP 
computePath (const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, int > &links, int from, int to, bool updateNewCosts=false)
float RTABMAP_EXP computePathLength (const std::vector< std::pair< int, Transform > > &path, unsigned int fromIndex=0, unsigned int toIndex=0)
std::multimap< int, Link >
::iterator RTABMAP_EXP 
findLink (std::multimap< int, Link > &links, int from, int to)
std::multimap< int, int >
::iterator RTABMAP_EXP 
findLink (std::multimap< int, int > &links, int from, int to)
int RTABMAP_EXP findNearestNode (const std::map< int, rtabmap::Transform > &nodes, const rtabmap::Transform &targetPose)
std::map< int, float > RTABMAP_EXP getNodesInRadius (int nodeId, const std::map< int, Transform > &nodes, float radius)
std::map< int, Transform >
RTABMAP_EXP 
getPosesInRadius (int nodeId, const std::map< int, Transform > &nodes, float radius)
std::multimap< int, int >
RTABMAP_EXP 
radiusPosesClustering (const std::map< int, Transform > &poses, float radius, float angle)
std::map< int, Transform >
RTABMAP_EXP 
radiusPosesFiltering (const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)

Typedef Documentation

typedef std::pair<int, float> rtabmap::graph::Pair

Definition at line 1142 of file Graph.cpp.


Function Documentation

std::list< std::pair< int, Transform > > rtabmap::graph::computePath ( const std::map< int, rtabmap::Transform > &  poses,
const std::multimap< int, int > &  links,
int  from,
int  to,
bool  updateNewCosts = false 
)

Perform A* path planning in the graph.

Parameters:
posesThe graph's poses
linksThe graph's links (from node id -> to node id)
frominitial node
tofinal node
updateNewCostsKeep up-to-date costs while traversing the graph.
Returns:
the path ids from id "from" to id "to" including initial and final nodes.

Definition at line 1151 of file Graph.cpp.

float rtabmap::graph::computePathLength ( const std::vector< std::pair< int, Transform > > &  path,
unsigned int  fromIndex = 0,
unsigned int  toIndex = 0 
)

Definition at line 1392 of file Graph.cpp.

std::multimap< int, Link >::iterator rtabmap::graph::findLink ( std::multimap< int, Link > &  links,
int  from,
int  to 
)

Definition at line 882 of file Graph.cpp.

std::multimap< int, int >::iterator rtabmap::graph::findLink ( std::multimap< int, int > &  links,
int  from,
int  to 
)

Definition at line 910 of file Graph.cpp.

int rtabmap::graph::findNearestNode ( const std::map< int, rtabmap::Transform > &  nodes,
const rtabmap::Transform targetPose 
)

Definition at line 1250 of file Graph.cpp.

std::map< int, float > rtabmap::graph::getNodesInRadius ( int  nodeId,
const std::map< int, Transform > &  nodes,
float  radius 
)

Get nodes near the query

Parameters:
nodeIdthe query id
nodesthe nodes to search for
maxNearestNeighborsMaximum nearest neighbor to get. 0 means all.
radiusradius to search for (m)
Returns:
the nodes with squared distance to query node.

Definition at line 1287 of file Graph.cpp.

std::map< int, Transform > rtabmap::graph::getPosesInRadius ( int  nodeId,
const std::map< int, Transform > &  nodes,
float  radius 
)

Definition at line 1340 of file Graph.cpp.

std::multimap< int, int > rtabmap::graph::radiusPosesClustering ( const std::map< int, Transform > &  poses,
float  radius,
float  angle 
)

Get all neighbor nodes in a fixed radius around each pose.

Parameters:
posesThe poses
radiusRadius (m) of the search for near neighbors
angleMaximum angle (rad, [0,PI]) of accepted neighbor nodes in the radius (0 means ignore angle)
Returns:
A map between each pose id and its neighbors found in the radius

Definition at line 1046 of file Graph.cpp.

std::map< int, Transform > rtabmap::graph::radiusPosesFiltering ( const std::map< int, Transform > &  poses,
float  radius,
float  angle,
bool  keepLatest = true 
)

Get only the the most recent or older poses in the defined radius.

Parameters:
posesThe poses
radiusRadius (m) of the search for near neighbors
angleMaximum angle (rad, [0,PI]) of accepted neighbor nodes in the radius (0 means ignore angle)
keepLatestkeep the latest node if true, otherwise the oldest node is kept
Returns:
A map containing only most recent or older poses in the the defined radius

Definition at line 938 of file Graph.cpp.



rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:44