Classes | |
| struct | errors |
| class | Node |
| struct | Order |
Typedefs | |
| typedef std::pair< int, float > | Pair |
Functions | |
| void RTABMAP_EXP | calcKittiSequenceErrors (const std::vector< Transform > &poses_gt, const std::vector< Transform > &poses_result, float &t_err, float &r_err) |
| void RTABMAP_EXP | calcRelativeErrors (const std::vector< Transform > &poses_gt, const std::vector< Transform > &poses_result, float &t_err, float &r_err) |
| Transform RTABMAP_EXP | calcRMSE (const std::map< int, Transform > &groundTruth, const std::map< int, Transform > &poses, float &translational_rmse, float &translational_mean, float &translational_median, float &translational_std, float &translational_min, float &translational_max, float &rotational_rmse, float &rotational_mean, float &rotational_median, float &rotational_std, float &rotational_min, float &rotational_max) |
| void RTABMAP_EXP | computeMaxGraphErrors (const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, float &maxLinearErrorRatio, float &maxAngularErrorRatio, float &maxLinearError, float &maxAngularError, const Link **maxLinearErrorLink=0, const Link **maxAngularErrorLink=0) |
| 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) |
| std::list< int > RTABMAP_EXP | computePath (const std::multimap< int, Link > &links, int from, int to, bool updateNewCosts=false, bool useSameCostForAllLinks=false) |
| std::list< std::pair< int, Transform > > RTABMAP_EXP | computePath (int fromId, int toId, const Memory *memory, bool lookInDatabase=true, bool updateNewCosts=false, float linearVelocity=0.0f, float angularVelocity=0.0f) |
| float RTABMAP_EXP | computePathLength (const std::vector< std::pair< int, Transform > > &path, unsigned int fromIndex=0, unsigned int toIndex=0) |
| float RTABMAP_EXP | computePathLength (const std::map< int, Transform > &path) |
| bool RTABMAP_EXP | exportGPS (const std::string &filePath, const std::map< int, GPS > &gpsValues, unsigned int rgba=0xFFFFFFFF) |
| bool RTABMAP_EXP | exportPoses (const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), const ParametersMap ¶meters=ParametersMap()) |
| std::multimap< int, Link > RTABMAP_EXP | filterDuplicateLinks (const std::multimap< int, Link > &links) |
| std::multimap< int, Link > RTABMAP_EXP | filterLinks (const std::multimap< int, Link > &links, Link::Type filteredType, bool inverted=false) |
| std::map< int, Link > RTABMAP_EXP | filterLinks (const std::map< int, Link > &links, Link::Type filteredType, bool inverted=false) |
| std::multimap< int, Link >::iterator RTABMAP_EXP | findLink (std::multimap< int, Link > &links, int from, int to, bool checkBothWays=true) |
| std::multimap< int, int >::iterator RTABMAP_EXP | findLink (std::multimap< int, int > &links, int from, int to, bool checkBothWays=true) |
| std::multimap< int, Link >::const_iterator RTABMAP_EXP | findLink (const std::multimap< int, Link > &links, int from, int to, bool checkBothWays=true, Link::Type type=Link::kUndef) |
| std::multimap< int, int >::const_iterator RTABMAP_EXP | findLink (const std::multimap< int, int > &links, int from, int to, bool checkBothWays=true) |
| std::list< Link > RTABMAP_EXP | findLinks (const std::multimap< int, Link > &links, int from) |
| int RTABMAP_EXP | findNearestNode (const std::map< int, rtabmap::Transform > &nodes, const rtabmap::Transform &targetPose, float *distance=0) |
| std::map< int, float > RTABMAP_EXP | findNearestNodes (const std::map< int, rtabmap::Transform > &nodes, const rtabmap::Transform &targetPose, int k) |
| std::map< int, Transform > RTABMAP_EXP | frustumPosesFiltering (const std::map< int, Transform > &poses, const Transform &cameraPose, float horizontalFOV=45.0f, float verticalFOV=45.0f, float nearClipPlaneDistance=0.1f, float farClipPlaneDistance=100.0f, bool negative=false) |
| std::vector< double > RTABMAP_EXP | getMaxOdomInf (const std::multimap< int, Link > &links) |
| std::map< int, float > RTABMAP_EXP | getNodesInRadius (int nodeId, const std::map< int, Transform > &nodes, float radius) |
| std::map< int, float > RTABMAP_EXP | getNodesInRadius (const Transform &targetPose, const std::map< int, Transform > &nodes, float radius) |
| std::list< std::map< int, Transform > > RTABMAP_EXP | getPaths (std::map< int, Transform > poses, const std::multimap< int, Link > &links) |
| std::map< int, Transform > RTABMAP_EXP | getPosesInRadius (int nodeId, const std::map< int, Transform > &nodes, float radius, float angle=0.0f) |
| std::map< int, Transform > RTABMAP_EXP | getPosesInRadius (const Transform &targetPose, const std::map< int, Transform > &nodes, float radius, float angle=0.0f) |
| bool RTABMAP_EXP | importPoses (const std::string &filePath, int format, std::map< int, Transform > &poses, std::multimap< int, Link > *constraints=0, std::map< int, double > *stamps=0) |
| int32_t | lastFrameFromSegmentLength (std::vector< float > &dist, int32_t first_frame, float len) |
| 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) |
| void | reduceGraph (const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, std::multimap< int, int > &hyperNodes, std::multimap< int, Link > &hyperLinks) |
| float | rotationError (const Transform &pose_error) |
| std::vector< float > | trajectoryDistances (const std::vector< Transform > &poses) |
| float | translationError (const Transform &pose_error) |
Variables | |
| float | lengths [] = {100,200,300,400,500,600,700,800} |
| int32_t | num_lengths = 8 |
| typedef std::pair<int, float> rtabmap::graph::Pair |
| void rtabmap::graph::calcKittiSequenceErrors | ( | const std::vector< Transform > & | poses_gt, |
| const std::vector< Transform > & | poses_result, | ||
| float & | t_err, | ||
| float & | r_err | ||
| ) |
Compute translation and rotation errors for KITTI datasets. See http://www.cvlibs.net/datasets/kitti/eval_odometry.php.
| poses_gt,Ground | Truth poses |
| poses_result,Estimated | poses |
| t_err,Output | translation error (%) |
| r_err,Output | rotation error (deg/m) |
| Transform rtabmap::graph::calcRMSE | ( | const std::map< int, Transform > & | groundTruth, |
| const std::map< int, Transform > & | poses, | ||
| float & | translational_rmse, | ||
| float & | translational_mean, | ||
| float & | translational_median, | ||
| float & | translational_std, | ||
| float & | translational_min, | ||
| float & | translational_max, | ||
| float & | rotational_rmse, | ||
| float & | rotational_mean, | ||
| float & | rotational_median, | ||
| float & | rotational_std, | ||
| float & | rotational_min, | ||
| float & | rotational_max | ||
| ) |
Compute root-mean-square error (RMSE) like the TUM RGBD dataset's evaluation tool (absolute trajectory error). See https://vision.in.tum.de/data/datasets/rgbd-dataset
| groundTruth,Ground | Truth poses |
| poses,Estimated | poses |
| void rtabmap::graph::computeMaxGraphErrors | ( | const std::map< int, Transform > & | poses, |
| const std::multimap< int, Link > & | links, | ||
| float & | maxLinearErrorRatio, | ||
| float & | maxAngularErrorRatio, | ||
| float & | maxLinearError, | ||
| float & | maxAngularError, | ||
| const Link ** | maxLinearErrorLink = 0, |
||
| const Link ** | maxAngularErrorLink = 0 |
||
| ) |
| 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. |
| std::list< int > RTABMAP_EXP rtabmap::graph::computePath | ( | const std::multimap< int, Link > & | links, |
| int | from, | ||
| int | to, | ||
| bool | updateNewCosts = false, |
||
| bool | useSameCostForAllLinks = false |
||
| ) |
Perform Dijkstra 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. |
| useSameCostForAllLinks | Ignore distance between nodes |
| std::list< std::pair< int, Transform > > rtabmap::graph::computePath | ( | int | fromId, |
| int | toId, | ||
| const Memory * | memory, | ||
| bool | lookInDatabase = true, |
||
| bool | updateNewCosts = false, |
||
| float | linearVelocity = 0.0f, |
||
| float | angularVelocity = 0.0f |
||
| ) |
Perform Dijkstra path planning in the graph.
| fromId | initial node |
| toId | final node |
| memory | The graph's memory |
| lookInDatabase | check links in database |
| 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 |
||
| ) |
| float rtabmap::graph::computePathLength | ( | const std::map< int, Transform > & | path | ) |
| bool rtabmap::graph::exportGPS | ( | const std::string & | filePath, |
| const std::map< int, GPS > & | gpsValues, | ||
| unsigned int | rgba = 0xFFFFFFFF |
||
| ) |
| bool rtabmap::graph::exportPoses | ( | const std::string & | filePath, |
| int | format, | ||
| const std::map< int, Transform > & | poses, | ||
| const std::multimap< int, Link > & | constraints = std::multimap<int, Link>(), |
||
| const std::map< int, double > & | stamps = std::map<int, double>(), |
||
| const ParametersMap & | parameters = ParametersMap() |
||
| ) |
| std::multimap< int, Link > rtabmap::graph::filterLinks | ( | const std::multimap< int, Link > & | links, |
| Link::Type | filteredType, | ||
| bool | inverted = false |
||
| ) |
| std::map< int, Link > rtabmap::graph::filterLinks | ( | const std::map< int, Link > & | links, |
| Link::Type | filteredType, | ||
| bool | inverted = false |
||
| ) |
| std::multimap< int, int >::iterator rtabmap::graph::findLink | ( | std::multimap< int, int > & | links, |
| int | from, | ||
| int | to, | ||
| bool | checkBothWays = true |
||
| ) |
| std::multimap< int, Link >::const_iterator rtabmap::graph::findLink | ( | const std::multimap< int, Link > & | links, |
| int | from, | ||
| int | to, | ||
| bool | checkBothWays = true, |
||
| Link::Type | type = Link::kUndef |
||
| ) |
| std::multimap< int, int >::const_iterator rtabmap::graph::findLink | ( | const std::multimap< int, int > & | links, |
| int | from, | ||
| int | to, | ||
| bool | checkBothWays = true |
||
| ) |
| int rtabmap::graph::findNearestNode | ( | const std::map< int, rtabmap::Transform > & | nodes, |
| const rtabmap::Transform & | targetPose, | ||
| float * | distance = 0 |
||
| ) |
| std::map< int, float > rtabmap::graph::findNearestNodes | ( | const std::map< int, rtabmap::Transform > & | nodes, |
| const rtabmap::Transform & | targetPose, | ||
| int | k | ||
| ) |
| std::vector< double > rtabmap::graph::getMaxOdomInf | ( | const std::multimap< int, Link > & | links | ) |
| std::map< int, float > rtabmap::graph::getNodesInRadius | ( | int | nodeId, |
| const std::map< int, Transform > & | nodes, | ||
| float | radius | ||
| ) |
| int32_t rtabmap::graph::lastFrameFromSegmentLength | ( | std::vector< float > & | dist, |
| int32_t | first_frame, | ||
| float | len | ||
| ) |
| 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 |
|
inline |
| std::vector<float> rtabmap::graph::trajectoryDistances | ( | const std::vector< Transform > & | poses | ) |
|
inline |
| float rtabmap::graph::lengths[] = {100,200,300,400,500,600,700,800} |