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 std::pair<int, float> rtabmap::graph::Pair |
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.
poses | The graph's poses |
links | The graph's links (from node id -> to node id) |
from | initial node |
to | final node |
updateNewCosts | Keep up-to-date costs while traversing the graph. |
float rtabmap::graph::computePathLength | ( | const std::vector< std::pair< int, Transform > > & | path, |
unsigned int | fromIndex = 0 , |
||
unsigned int | toIndex = 0 |
||
) |
std::multimap< int, Link >::iterator rtabmap::graph::findLink | ( | std::multimap< int, Link > & | links, |
int | from, | ||
int | to | ||
) |
std::multimap< int, int >::iterator rtabmap::graph::findLink | ( | std::multimap< int, int > & | links, |
int | from, | ||
int | to | ||
) |
int rtabmap::graph::findNearestNode | ( | const std::map< int, rtabmap::Transform > & | nodes, |
const rtabmap::Transform & | targetPose | ||
) |
std::map< int, float > rtabmap::graph::getNodesInRadius | ( | int | nodeId, |
const std::map< int, Transform > & | nodes, | ||
float | radius | ||
) |
std::map< int, Transform > rtabmap::graph::getPosesInRadius | ( | int | nodeId, |
const std::map< int, Transform > & | nodes, | ||
float | radius | ||
) |
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.
poses | The poses |
radius | Radius (m) of the search for near neighbors |
angle | Maximum angle (rad, [0,PI]) of accepted neighbor nodes in the radius (0 means ignore angle) |
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.
poses | The poses |
radius | Radius (m) of the search for near neighbors |
angle | Maximum angle (rad, [0,PI]) of accepted neighbor nodes in the radius (0 means ignore angle) |
keepLatest | keep the latest node if true, otherwise the oldest node is kept |