Classes | Typedefs | Functions | Variables
rtabmap::graph Namespace Reference

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 &parameters=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 Documentation

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

Definition at line 1624 of file Graph.cpp.

Function Documentation

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.

Parameters
poses_gt,GroundTruth poses
poses_result,Estimatedposes
t_err,Outputtranslation error (%)
r_err,Outputrotation error (deg/m)

Definition at line 627 of file Graph.cpp.

void rtabmap::graph::calcRelativeErrors ( const std::vector< Transform > &  poses_gt,
const std::vector< Transform > &  poses_result,
float &  t_err,
float &  r_err 
)

Compute average of translation and rotation errors between each poses.

Parameters
poses_gt,GroundTruth poses
poses_result,Estimatedposes
t_err,Outputtranslation error (m)
r_err,Outputrotation error (deg)

Definition at line 695 of file Graph.cpp.

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

Parameters
groundTruth,GroundTruth poses
poses,Estimatedposes
Returns
Gt to Map transform

Definition at line 737 of file Graph.cpp.

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 
)

Definition at line 874 of file Graph.cpp.

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 1634 of file Graph.cpp.

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.

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.
useSameCostForAllLinksIgnore distance between nodes
Returns
the path ids from id "from" to id "to" including initial and final nodes.

Definition at line 1740 of file Graph.cpp.

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.

Parameters
fromIdinitial node
toIdfinal node
memoryThe graph's memory
lookInDatabasecheck links in database
updateNewCostsKeep up-to-date costs while traversing the graph.
Returns
the path ids from id "fromId" to id "toId" including initial and final nodes (Identity pose for the first node).

Definition at line 1842 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 2250 of file Graph.cpp.

float rtabmap::graph::computePathLength ( const std::map< int, Transform > &  path)

Definition at line 2275 of file Graph.cpp.

bool rtabmap::graph::exportGPS ( const std::string &  filePath,
const std::map< int, GPS > &  gpsValues,
unsigned int  rgba = 0xFFFFFFFF 
)

Definition at line 478 of file Graph.cpp.

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() 
)

Definition at line 54 of file Graph.cpp.

std::multimap< int, Link > rtabmap::graph::filterDuplicateLinks ( const std::multimap< int, Link > &  links)

Definition at line 1116 of file Graph.cpp.

std::multimap< int, Link > rtabmap::graph::filterLinks ( const std::multimap< int, Link > &  links,
Link::Type  filteredType,
bool  inverted = false 
)

Return links not of type "filteredType". If inverted=true, return links of of type "filteredType".

Definition at line 1130 of file Graph.cpp.

std::map< int, Link > rtabmap::graph::filterLinks ( const std::map< int, Link > &  links,
Link::Type  filteredType,
bool  inverted = false 
)

Return links not of type "filteredType". If inverted=true, return links of of type "filteredType".

Definition at line 1155 of file Graph.cpp.

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

Definition at line 969 of file Graph.cpp.

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

Definition at line 1001 of file Graph.cpp.

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 
)

Definition at line 1032 of file Graph.cpp.

std::multimap< int, int >::const_iterator rtabmap::graph::findLink ( const std::multimap< int, int > &  links,
int  from,
int  to,
bool  checkBothWays = true 
)

Definition at line 1065 of file Graph.cpp.

std::list< Link > rtabmap::graph::findLinks ( const std::multimap< int, Link > &  links,
int  from 
)

Definition at line 1097 of file Graph.cpp.

int rtabmap::graph::findNearestNode ( const std::map< int, rtabmap::Transform > &  nodes,
const rtabmap::Transform targetPose,
float *  distance = 0 
)

Get the nearest node of the target pose

Parameters
nodesthe nodes to search for
targetPosethe target pose to search around
distancesquared distance of the nearest node found (optional)
Returns
the node id.

Definition at line 2061 of file Graph.cpp.

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

Get K nearest nodes of the target pose

Parameters
nodesthe nodes to search for
targetPosethe target pose to search around
knumber of nearest neighbors to search for
Returns
the node ids with squared distance to target pose.

Definition at line 2079 of file Graph.cpp.

std::map< int, Transform > rtabmap::graph::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 
)

Definition at line 1180 of file Graph.cpp.

std::vector< double > rtabmap::graph::getMaxOdomInf ( const std::multimap< int, Link > &  links)

Definition at line 941 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
radiusradius to search for (m)
Returns
the nodes with squared distance to query node.

Definition at line 2113 of file Graph.cpp.

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

Definition at line 2127 of file Graph.cpp.

std::list< std::map< int, Transform > > rtabmap::graph::getPaths ( std::map< int, Transform poses,
const std::multimap< int, Link > &  links 
)

Definition at line 2299 of file Graph.cpp.

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

Definition at line 2173 of file Graph.cpp.

std::map< int, Transform > rtabmap::graph::getPosesInRadius ( const Transform targetPose,
const std::map< int, Transform > &  nodes,
float  radius,
float  angle = 0.0f 
)

Definition at line 2187 of file Graph.cpp.

bool rtabmap::graph::importPoses ( const std::string &  filePath,
int  format,
std::map< int, Transform > &  poses,
std::multimap< int, Link > *  constraints = 0,
std::map< int, double > *  stamps = 0 
)

Definition at line 170 of file Graph.cpp.

int32_t rtabmap::graph::lastFrameFromSegmentLength ( std::vector< float > &  dist,
int32_t  first_frame,
float  len 
)

Definition at line 605 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 1341 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 1229 of file Graph.cpp.

void rtabmap::graph::reduceGraph ( const std::map< int, Transform > &  poses,
const std::multimap< int, Link > &  links,
std::multimap< int, int > &  hyperNodes,
std::multimap< int, Link > &  hyperLinks 
)

Definition at line 1397 of file Graph.cpp.

float rtabmap::graph::rotationError ( const Transform pose_error)
inline

Definition at line 612 of file Graph.cpp.

std::vector<float> rtabmap::graph::trajectoryDistances ( const std::vector< Transform > &  poses)

Definition at line 591 of file Graph.cpp.

float rtabmap::graph::translationError ( const Transform pose_error)
inline

Definition at line 620 of file Graph.cpp.

Variable Documentation

float rtabmap::graph::lengths[] = {100,200,300,400,500,600,700,800}

Definition at line 578 of file Graph.cpp.

int32_t rtabmap::graph::num_lengths = 8

Definition at line 579 of file Graph.cpp.



rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:09