Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
rtabmap::Rtabmap Class Reference

#include <Rtabmap.h>

Public Types

enum  VhStrategy { kVhNone, kVhEpipolar, kVhUndef }
 

Public Member Functions

bool addLink (const Link &link)
 
void addNodesToRepublish (const std::vector< int > &ids)
 
void adjustLikelihood (std::map< int, float > &likelihood) const
 
int cleanupLocalGrids (const std::map< int, Transform > &mapPoses, const cv::Mat &map, float xMin, float yMin, float cellSize, int cropRadius=1, bool filterScans=false)
 
void clearPath (int status)
 
void close (bool databaseSaved=true, const std::string &ouputDatabasePath="")
 
bool computePath (int targetNode, bool global)
 
bool computePath (const Transform &targetPose, float tolerance=-1.0f)
 
void deleteLastLocation ()
 
int detectMoreLoopClosures (float clusterRadiusMax=0.5f, float clusterAngle=M_PI/6.0f, int iterations=1, bool intraSession=true, bool interSession=true, const ProgressState *state=0, float clusterRadiusMin=0.0f)
 
void dumpData () const
 
void dumpPrediction () const
 
void exportPoses (const std::string &path, bool optimized, bool global, int format)
 
void generateDOTGraph (const std::string &path, int id=0, int margin=5)
 
std::map< int, TransformgetForwardWMPoses (int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const
 
float getGoalReachedRadius () const
 
void getGraph (std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0, bool withImages=false, bool withScan=false, bool withUserData=false, bool withGrid=false, bool withWords=true, bool withGlobalDescriptors=true) const
 
int getHighestHypothesisId () const
 
float getHighestHypothesisValue () const
 
cv::Mat getInformation (const cv::Mat &covariance) const
 
const TransformgetLastLocalizationPose () const
 
int getLastLocationId () const
 
double getLastProcessTime () const
 
const std::multimap< int, Link > & getLocalConstraints () const
 
const std::map< int, Transform > & getLocalOptimizedPoses () const
 
float getLocalRadius () const
 
int getLoopClosureId () const
 
float getLoopClosureValue () const
 
Transform getMapCorrection () const
 
const MemorygetMemory () const
 
std::map< int, TransformgetNodesInRadius (const Transform &pose, float radius, int k=0, std::map< int, float > *distsSqr=0)
 
std::map< int, TransformgetNodesInRadius (int nodeId, float radius, int k=0, std::map< int, float > *distsSqr=0)
 
const ParametersMapgetParameters () const
 
const std::vector< std::pair< int, Transform > > & getPath () const
 
int getPathCurrentGoalId () const
 
unsigned int getPathCurrentGoalIndex () const
 
unsigned int getPathCurrentIndex () const
 
std::vector< int > getPathNextNodes () const
 
std::vector< std::pair< int, Transform > > getPathNextPoses () const
 
std::map< int, std::map< int, Transform > > getPaths (const std::map< int, Transform > &poses, const Transform &target, int maxGraphDepth=0) const
 
int getPathStatus () const
 
const TransformgetPathTransformToGoal () const
 
Transform getPose (int locationId) const
 
Signature getSignatureCopy (int id, bool images, bool scan, bool userData, bool occupancyGrid, bool withWords, bool withGlobalDescriptors) const
 
const StatisticsgetStatistics () const
 
std::set< int > getSTM () const
 
int getSTMSize () const
 
float getTimeThreshold () const
 
int getTotalMemSize () const
 
std::map< int, int > getWeights () const
 
std::list< int > getWM () const
 
int getWMSize () const
 
const std::stringgetWorkingDir () const
 
bool globalBundleAdjustment (int optimizerType=1, bool rematchFeatures=true, int iterations=0, float pixelVariance=0.0f)
 
void init (const ParametersMap &parameters, const std::string &databasePath="", bool loadDatabaseParameters=false)
 
void init (const std::string &configFile="", const std::string &databasePath="", bool loadDatabaseParameters=false)
 
bool isIDsGenerated () const
 
bool isInSTM (int locationId) const
 
bool isRGBDMode () const
 
bool labelLocation (int id, const std::string &label)
 
void parseParameters (const ParametersMap &parameters)
 
bool process (const SensorData &data, Transform odomPose, const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
 Main loop of rtabmap. More...
 
bool process (const SensorData &data, Transform odomPose, float odomLinearVariance, float odomAngularVariance, const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
 
bool process (const cv::Mat &image, int id=0, const std::map< std::string, float > &externalStats=std::map< std::string, float >())
 
int refineLinks ()
 
void rejectLastLoopClosure ()
 
void resetMemory ()
 
 Rtabmap ()
 
 RTABMAP_DEPRECATED (void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const, "Use getGraph() instead with withImages=true, withScan=true, withUserData=true and withGrid=true.")
 
std::pair< int, float > selectHypothesis (const std::map< int, float > &posterior, const std::map< int, float > &likelihood) const
 
void setInitialPose (const Transform &initialPose)
 
void setOptimizedPoses (const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints)
 
void setTimeThreshold (float maxTimeAllowed)
 
bool setUserData (int id, const cv::Mat &data)
 
void setWorkingDirectory (std::string path)
 
int triggerNewMap ()
 
virtual ~Rtabmap ()
 

Private Member Functions

bool computePath (int targetNode, std::map< int, Transform > nodes, const std::multimap< int, rtabmap::Link > &constraints)
 
void createGlobalScanMap ()
 
void flushStatisticLogs ()
 
void optimizeCurrentMap (int id, bool lookInDatabase, std::map< int, Transform > &optimizedPoses, cv::Mat &covariance, std::multimap< int, Link > *constraints=0, double *error=0, int *iterationsDone=0) const
 
std::map< int, TransformoptimizeGraph (int fromId, const std::set< int > &ids, const std::map< int, Transform > &guessPoses, bool lookInDatabase, cv::Mat &covariance, std::multimap< int, Link > *constraints=0, double *error=0, int *iterationsDone=0) const
 
void setupLogFiles (bool overwrite=false)
 
void updateGoalIndex ()
 

Private Attributes

BayesFilter_bayesFilter
 
std::list< std::string_bufferedLogsF
 
std::list< std::string_bufferedLogsI
 
bool _computeRMSE
 
std::multimap< int, Link_constraints
 
bool _createGlobalScanMap
 
bool _currentSessionHasGPS
 
std::string _databasePath
 
float _distanceTravelled
 
float _distanceTravelledSinceLastLocalization
 
EpipolarGeometry_epipolarGeometry
 
FILE * _foutFloat
 
FILE * _foutInt
 
LaserScan _globalScanMap
 
std::map< int, Transform_globalScanMapPoses
 
float _goalReachedRadius
 
bool _goalsSavedInUserData
 
std::map< int, std::pair< cv::Point3d, Transform > > _gpsGeocentricCache
 
Optimizer_graphOptimizer
 
std::pair< int, float > _highestHypothesis
 
int _lastLocalizationNodeId
 
Transform _lastLocalizationPose
 
double _lastProcessTime
 
float _localImmunizationRatio
 
float _localRadius
 
std::pair< int, float > _loopClosureHypothesis
 
bool _loopClosureIdentityGuess
 
bool _loopCovLimited
 
bool _loopGPS
 
float _loopRatio
 
float _loopThr
 
Transform _mapCorrection
 
Transform _mapCorrectionBackup
 
std::map< int, Transform_markerPriors
 
float _markerPriorsAngularVariance
 
float _markerPriorsLinearVariance
 
unsigned int _maxLocalRetrieved
 
float _maxLoopClosureDistance
 
unsigned int _maxMemoryAllowed
 
int _maxOdomCacheSize
 
unsigned int _maxRepublished
 
unsigned int _maxRetrieved
 
float _maxTimeAllowed
 
Memory_memory
 
bool _neighborLinkRefining
 
float _newMapOdomChangeDistance
 
std::set< int > _nodesToRepublish
 
std::multimap< int, Link_odomCacheConstraints
 
std::map< int, Transform_odomCachePoses
 
std::vector< float > _odomCorrectionAcc
 
float _optimizationMaxError
 
std::map< int, Transform_optimizedPoses
 
bool _optimizeFromGraphEnd
 
bool _optimizeFromGraphEndChanged
 
ParametersMap _parameters
 
std::vector< std::pair< int, Transform > > _path
 
float _pathAngularVelocity
 
unsigned int _pathCurrentIndex
 
unsigned int _pathGoalIndex
 
float _pathLinearVelocity
 
int _pathStatus
 
int _pathStuckCount
 
float _pathStuckDistance
 
int _pathStuckIterations
 
Transform _pathTransformToGoal
 
std::set< unsigned int > _pathUnreachableNodes
 
float _proximityAngle
 
bool _proximityBySpace
 
bool _proximityByTime
 
float _proximityFilteringRadius
 
int _proximityMaxGraphDepth
 
int _proximityMaxNeighbors
 
int _proximityMaxPaths
 
double _proximityMergedScanCovFactor
 
bool _proximityOdomGuess
 
bool _proximityRawPosesUsed
 
bool _publishLastSignatureData
 
bool _publishLikelihood
 
bool _publishPdf
 
bool _publishRAMUsage
 
bool _publishStats
 
bool _rawDataKept
 
bool _restartAtOrigin
 
float _rgbdAngularSpeedUpdate
 
float _rgbdAngularUpdate
 
float _rgbdLinearSpeedUpdate
 
float _rgbdLinearUpdate
 
bool _rgbdSlamMode
 
bool _saveWMState
 
bool _scanMatchingIdsSavedInLinks
 
bool _someNodesHaveBeenTransferred
 
bool _startNewMapOnGoodSignature
 
bool _startNewMapOnLoopClosure
 
bool _statisticLogged
 
bool _statisticLoggedHeaders
 
bool _statisticLogsBufferedInRAM
 
bool _verifyLoopClosureHypothesis
 
std::string _wDir
 
Statistics statistics_
 

Detailed Description

Definition at line 54 of file Rtabmap.h.

Member Enumeration Documentation

◆ VhStrategy

Enumerator
kVhNone 
kVhEpipolar 
kVhUndef 

Definition at line 57 of file Rtabmap.h.

Constructor & Destructor Documentation

◆ Rtabmap()

rtabmap::Rtabmap::Rtabmap ( )

Definition at line 88 of file Rtabmap.cpp.

◆ ~Rtabmap()

rtabmap::Rtabmap::~Rtabmap ( )
virtual

Definition at line 177 of file Rtabmap.cpp.

Member Function Documentation

◆ addLink()

bool rtabmap::Rtabmap::addLink ( const Link link)

Definition at line 5743 of file Rtabmap.cpp.

◆ addNodesToRepublish()

void rtabmap::Rtabmap::addNodesToRepublish ( const std::vector< int > &  ids)

Definition at line 6094 of file Rtabmap.cpp.

◆ adjustLikelihood()

void rtabmap::Rtabmap::adjustLikelihood ( std::map< int, float > &  likelihood) const

Definition at line 4970 of file Rtabmap.cpp.

◆ cleanupLocalGrids()

int rtabmap::Rtabmap::cleanupLocalGrids ( const std::map< int, Transform > &  mapPoses,
const cv::Mat &  map,
float  xMin,
float  yMin,
float  cellSize,
int  cropRadius = 1,
bool  filterScans = false 
)

Definition at line 5674 of file Rtabmap.cpp.

◆ clearPath()

void rtabmap::Rtabmap::clearPath ( int  status)

Definition at line 6114 of file Rtabmap.cpp.

◆ close()

void rtabmap::Rtabmap::close ( bool  databaseSaved = true,
const std::string ouputDatabasePath = "" 
)

Close rtabmap. This will delete rtabmap object if set.

Parameters
databaseSavedtrue=database saved, false=database discarded.
databasePathoutput database file name, ignored if Db/Sqlite3InMemory=false (opened database is then overwritten).

Definition at line 453 of file Rtabmap.cpp.

◆ computePath() [1/3]

bool rtabmap::Rtabmap::computePath ( int  targetNode,
bool  global 
)

Definition at line 6132 of file Rtabmap.cpp.

◆ computePath() [2/3]

bool rtabmap::Rtabmap::computePath ( const Transform targetPose,
float  tolerance = -1.0f 
)

Definition at line 6277 of file Rtabmap.cpp.

◆ computePath() [3/3]

bool rtabmap::Rtabmap::computePath ( int  targetNode,
std::map< int, Transform nodes,
const std::multimap< int, rtabmap::Link > &  constraints 
)
private

◆ createGlobalScanMap()

void rtabmap::Rtabmap::createGlobalScanMap ( )
private

Definition at line 6729 of file Rtabmap.cpp.

◆ deleteLastLocation()

void rtabmap::Rtabmap::deleteLastLocation ( )

Definition at line 4559 of file Rtabmap.cpp.

◆ detectMoreLoopClosures()

int rtabmap::Rtabmap::detectMoreLoopClosures ( float  clusterRadiusMax = 0.5f,
float  clusterAngle = M_PI/6.0f,
int  iterations = 1,
bool  intraSession = true,
bool  interSession = true,
const ProgressState state = 0,
float  clusterRadiusMin = 0.0f 
)

Definition at line 5305 of file Rtabmap.cpp.

◆ dumpData()

void rtabmap::Rtabmap::dumpData ( ) const

Definition at line 4615 of file Rtabmap.cpp.

◆ dumpPrediction()

void rtabmap::Rtabmap::dumpPrediction ( ) const

Definition at line 5041 of file Rtabmap.cpp.

◆ exportPoses()

void rtabmap::Rtabmap::exportPoses ( const std::string path,
bool  optimized,
bool  global,
int  format 
)

Definition at line 1005 of file Rtabmap.cpp.

◆ flushStatisticLogs()

void rtabmap::Rtabmap::flushStatisticLogs ( )
private

Definition at line 288 of file Rtabmap.cpp.

◆ generateDOTGraph()

void rtabmap::Rtabmap::generateDOTGraph ( const std::string path,
int  id = 0,
int  margin = 5 
)

Definition at line 973 of file Rtabmap.cpp.

◆ getForwardWMPoses()

std::map< int, Transform > rtabmap::Rtabmap::getForwardWMPoses ( int  fromId,
int  maxNearestNeighbors,
float  radius,
int  maxDiffID 
) const

Definition at line 4633 of file Rtabmap.cpp.

◆ getGoalReachedRadius()

float rtabmap::Rtabmap::getGoalReachedRadius ( ) const
inline

Definition at line 148 of file Rtabmap.h.

◆ getGraph()

void rtabmap::Rtabmap::getGraph ( std::map< int, Transform > &  poses,
std::multimap< int, Link > &  constraints,
bool  optimized,
bool  global,
std::map< int, Signature > *  signatures = 0,
bool  withImages = false,
bool  withScan = false,
bool  withUserData = false,
bool  withGrid = false,
bool  withWords = true,
bool  withGlobalDescriptors = true 
) const

Definition at line 5189 of file Rtabmap.cpp.

◆ getHighestHypothesisId()

int rtabmap::Rtabmap::getHighestHypothesisId ( ) const
inline

Definition at line 130 of file Rtabmap.h.

◆ getHighestHypothesisValue()

float rtabmap::Rtabmap::getHighestHypothesisValue ( ) const
inline

Definition at line 131 of file Rtabmap.h.

◆ getInformation()

cv::Mat rtabmap::Rtabmap::getInformation ( const cv::Mat &  covariance) const

Definition at line 6074 of file Rtabmap.cpp.

◆ getLastLocalizationPose()

const Transform& rtabmap::Rtabmap::getLastLocalizationPose ( ) const
inline

Definition at line 150 of file Rtabmap.h.

◆ getLastLocationId()

int rtabmap::Rtabmap::getLastLocationId ( ) const

Definition at line 740 of file Rtabmap.cpp.

◆ getLastProcessTime()

double rtabmap::Rtabmap::getLastProcessTime ( ) const
inline

Definition at line 139 of file Rtabmap.h.

◆ getLocalConstraints()

const std::multimap<int, Link>& rtabmap::Rtabmap::getLocalConstraints ( ) const
inline

Definition at line 144 of file Rtabmap.h.

◆ getLocalOptimizedPoses()

const std::map<int, Transform>& rtabmap::Rtabmap::getLocalOptimizedPoses ( ) const
inline

Definition at line 143 of file Rtabmap.h.

◆ getLocalRadius()

float rtabmap::Rtabmap::getLocalRadius ( ) const
inline

Definition at line 149 of file Rtabmap.h.

◆ getLoopClosureId()

int rtabmap::Rtabmap::getLoopClosureId ( ) const
inline

Definition at line 128 of file Rtabmap.h.

◆ getLoopClosureValue()

float rtabmap::Rtabmap::getLoopClosureValue ( ) const
inline

Definition at line 129 of file Rtabmap.h.

◆ getMapCorrection()

Transform rtabmap::Rtabmap::getMapCorrection ( ) const
inline

Definition at line 146 of file Rtabmap.h.

◆ getMemory()

const Memory* rtabmap::Rtabmap::getMemory ( ) const
inline

Definition at line 147 of file Rtabmap.h.

◆ getNodesInRadius() [1/2]

std::map< int, Transform > rtabmap::Rtabmap::getNodesInRadius ( const Transform pose,
float  radius,
int  k = 0,
std::map< int, float > *  distsSqr = 0 
)

Definition at line 5261 of file Rtabmap.cpp.

◆ getNodesInRadius() [2/2]

std::map< int, Transform > rtabmap::Rtabmap::getNodesInRadius ( int  nodeId,
float  radius,
int  k = 0,
std::map< int, float > *  distsSqr = 0 
)

Definition at line 5274 of file Rtabmap.cpp.

◆ getParameters()

const ParametersMap& rtabmap::Rtabmap::getParameters ( ) const
inline

Definition at line 177 of file Rtabmap.h.

◆ getPath()

const std::vector<std::pair<int, Transform> >& rtabmap::Rtabmap::getPath ( ) const
inline

Definition at line 232 of file Rtabmap.h.

◆ getPathCurrentGoalId()

int rtabmap::Rtabmap::getPathCurrentGoalId ( ) const

Definition at line 6456 of file Rtabmap.cpp.

◆ getPathCurrentGoalIndex()

unsigned int rtabmap::Rtabmap::getPathCurrentGoalIndex ( ) const
inline

Definition at line 237 of file Rtabmap.h.

◆ getPathCurrentIndex()

unsigned int rtabmap::Rtabmap::getPathCurrentIndex ( ) const
inline

Definition at line 236 of file Rtabmap.h.

◆ getPathNextNodes()

std::vector< int > rtabmap::Rtabmap::getPathNextNodes ( ) const

Definition at line 6431 of file Rtabmap.cpp.

◆ getPathNextPoses()

std::vector< std::pair< int, Transform > > rtabmap::Rtabmap::getPathNextPoses ( ) const

Definition at line 6406 of file Rtabmap.cpp.

◆ getPaths()

std::map< int, std::map< int, Transform > > rtabmap::Rtabmap::getPaths ( const std::map< int, Transform > &  poses,
const Transform target,
int  maxGraphDepth = 0 
) const

Definition at line 4749 of file Rtabmap.cpp.

◆ getPathStatus()

int rtabmap::Rtabmap::getPathStatus ( ) const
inline

Definition at line 228 of file Rtabmap.h.

◆ getPathTransformToGoal()

const Transform& rtabmap::Rtabmap::getPathTransformToGoal ( ) const
inline

Definition at line 238 of file Rtabmap.h.

◆ getPose()

Transform rtabmap::Rtabmap::getPose ( int  locationId) const

Definition at line 835 of file Rtabmap.cpp.

◆ getSignatureCopy()

Signature rtabmap::Rtabmap::getSignatureCopy ( int  id,
bool  images,
bool  scan,
bool  userData,
bool  occupancyGrid,
bool  withWords,
bool  withGlobalDescriptors 
) const

Definition at line 5099 of file Rtabmap.cpp.

◆ getStatistics()

const Statistics & rtabmap::Rtabmap::getStatistics ( ) const

Definition at line 830 of file Rtabmap.cpp.

◆ getSTM()

std::set< int > rtabmap::Rtabmap::getSTM ( ) const

Definition at line 781 of file Rtabmap.cpp.

◆ getSTMSize()

int rtabmap::Rtabmap::getSTMSize ( ) const

Definition at line 790 of file Rtabmap.cpp.

◆ getTimeThreshold()

float rtabmap::Rtabmap::getTimeThreshold ( ) const
inline

Definition at line 152 of file Rtabmap.h.

◆ getTotalMemSize()

int rtabmap::Rtabmap::getTotalMemSize ( ) const

Definition at line 799 of file Rtabmap.cpp.

◆ getWeights()

std::map< int, int > rtabmap::Rtabmap::getWeights ( ) const

Definition at line 770 of file Rtabmap.cpp.

◆ getWM()

std::list< int > rtabmap::Rtabmap::getWM ( ) const

Definition at line 750 of file Rtabmap.cpp.

◆ getWMSize()

int rtabmap::Rtabmap::getWMSize ( ) const

Definition at line 761 of file Rtabmap.cpp.

◆ getWorkingDir()

const std::string& rtabmap::Rtabmap::getWorkingDir ( ) const
inline

Definition at line 126 of file Rtabmap.h.

◆ globalBundleAdjustment()

bool rtabmap::Rtabmap::globalBundleAdjustment ( int  optimizerType = 1,
bool  rematchFeatures = true,
int  iterations = 0,
float  pixelVariance = 0.0f 
)

Definition at line 5615 of file Rtabmap.cpp.

◆ init() [1/2]

void rtabmap::Rtabmap::init ( const ParametersMap parameters,
const std::string databasePath = "",
bool  loadDatabaseParameters = false 
)

Initialize Rtabmap with parameters and a database

Parameters
parametersParameters overriding default parameters and database parameters (
See also
loadDatabaseParameters)
Parameters
databasePathThe database input/output path. If not set, an empty database is used in RAM. If set and the file doesn't exist, it will be created empty. If the database exists, nodes and vocabulary will be loaded in working memory.
loadDatabaseParametersIf an existing database is used (
See also
databasePath), the parameters inside are loaded and set to current Rtabmap instance.

Definition at line 310 of file Rtabmap.cpp.

◆ init() [2/2]

void rtabmap::Rtabmap::init ( const std::string configFile = "",
const std::string databasePath = "",
bool  loadDatabaseParameters = false 
)

Initialize Rtabmap with parameters from a configuration file and a database

Parameters
configFileConfiguration file (*.ini) overriding default parameters and database parameters (
See also
loadDatabaseParameters)
Parameters
databasePathThe database input/output path. If not set, an empty database is used in RAM. If set and the file doesn't exist, it will be created empty. If the database exists, nodes and vocabulary will be loaded in working memory.
loadDatabaseParametersIf an existing database is used (
See also
databasePath), the parameters inside are loaded and set to current Rtabmap instance.

Definition at line 439 of file Rtabmap.cpp.

◆ isIDsGenerated()

bool rtabmap::Rtabmap::isIDsGenerated ( ) const

Definition at line 821 of file Rtabmap.cpp.

◆ isInSTM()

bool rtabmap::Rtabmap::isInSTM ( int  locationId) const

Definition at line 812 of file Rtabmap.cpp.

◆ isRGBDMode()

bool rtabmap::Rtabmap::isRGBDMode ( ) const
inline

Definition at line 127 of file Rtabmap.h.

◆ labelLocation()

bool rtabmap::Rtabmap::labelLocation ( int  id,
const std::string label 
)

Definition at line 917 of file Rtabmap.cpp.

◆ optimizeCurrentMap()

void rtabmap::Rtabmap::optimizeCurrentMap ( int  id,
bool  lookInDatabase,
std::map< int, Transform > &  optimizedPoses,
cv::Mat &  covariance,
std::multimap< int, Link > *  constraints = 0,
double *  error = 0,
int *  iterationsDone = 0 
) const
private

Definition at line 4831 of file Rtabmap.cpp.

◆ optimizeGraph()

std::map< int, Transform > rtabmap::Rtabmap::optimizeGraph ( int  fromId,
const std::set< int > &  ids,
const std::map< int, Transform > &  guessPoses,
bool  lookInDatabase,
cv::Mat &  covariance,
std::multimap< int, Link > *  constraints = 0,
double *  error = 0,
int *  iterationsDone = 0 
) const
private

Definition at line 4877 of file Rtabmap.cpp.

◆ parseParameters()

void rtabmap::Rtabmap::parseParameters ( const ParametersMap parameters)

Definition at line 535 of file Rtabmap.cpp.

◆ process() [1/3]

bool rtabmap::Rtabmap::process ( const SensorData data,
Transform  odomPose,
const cv::Mat &  odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
const std::vector< float > &  odomVelocity = std::vector<float>(),
const std::map< std::string, float > &  externalStats = std::map<std::string, float>() 
)

Main loop of rtabmap.

Parameters
dataSensor data to process.
odomPoseOdometry pose, should be non-null for RGB-D SLAM mode.
covarianceOdometry covariance.
externalStatsExternal statistics to be saved in the database for convenience
Returns
true if data has been added to map.

Definition at line 1151 of file Rtabmap.cpp.

◆ process() [2/3]

bool rtabmap::Rtabmap::process ( const SensorData data,
Transform  odomPose,
float  odomLinearVariance,
float  odomAngularVariance,
const std::vector< float > &  odomVelocity = std::vector<float>(),
const std::map< std::string, float > &  externalStats = std::map<std::string, float>() 
)

Definition at line 1129 of file Rtabmap.cpp.

◆ process() [3/3]

bool rtabmap::Rtabmap::process ( const cv::Mat &  image,
int  id = 0,
const std::map< std::string, float > &  externalStats = std::map<std::string, float>() 
)

Definition at line 1122 of file Rtabmap.cpp.

◆ refineLinks()

int rtabmap::Rtabmap::refineLinks ( )

Definition at line 5697 of file Rtabmap.cpp.

◆ rejectLastLoopClosure()

void rtabmap::Rtabmap::rejectLastLoopClosure ( )

Definition at line 4501 of file Rtabmap.cpp.

◆ resetMemory()

void rtabmap::Rtabmap::resetMemory ( )

Definition at line 1044 of file Rtabmap.cpp.

◆ RTABMAP_DEPRECATED()

rtabmap::Rtabmap::RTABMAP_DEPRECATED ( void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global)  const,
"Use getGraph() instead with  withImages = true,
withScan  = true 
)

◆ selectHypothesis()

std::pair<int, float> rtabmap::Rtabmap::selectHypothesis ( const std::map< int, float > &  posterior,
const std::map< int, float > &  likelihood 
) const

◆ setInitialPose()

void rtabmap::Rtabmap::setInitialPose ( const Transform initialPose)

Definition at line 840 of file Rtabmap.cpp.

◆ setOptimizedPoses()

void rtabmap::Rtabmap::setOptimizedPoses ( const std::map< int, Transform > &  poses,
const std::multimap< int, Link > &  constraints 
)

Definition at line 4609 of file Rtabmap.cpp.

◆ setTimeThreshold()

void rtabmap::Rtabmap::setTimeThreshold ( float  maxTimeAllowed)

Definition at line 4458 of file Rtabmap.cpp.

◆ setupLogFiles()

void rtabmap::Rtabmap::setupLogFiles ( bool  overwrite = false)
private

Definition at line 182 of file Rtabmap.cpp.

◆ setUserData()

bool rtabmap::Rtabmap::setUserData ( int  id,
const cv::Mat &  data 
)

Set user data. Detect automatically if raw or compressed. If raw, the data is compressed too. A matrix of type CV_8UC1 with 1 row is considered as compressed. If you have one dimension unsigned 8 bits raw data, make sure to transpose it (to have multiple rows instead of multiple columns) in order to be detected as not compressed.

Definition at line 953 of file Rtabmap.cpp.

◆ setWorkingDirectory()

void rtabmap::Rtabmap::setWorkingDirectory ( std::string  path)

Definition at line 4473 of file Rtabmap.cpp.

◆ triggerNewMap()

int rtabmap::Rtabmap::triggerNewMap ( )

Definition at line 868 of file Rtabmap.cpp.

◆ updateGoalIndex()

void rtabmap::Rtabmap::updateGoalIndex ( )
private

Definition at line 6466 of file Rtabmap.cpp.

Member Data Documentation

◆ _bayesFilter

BayesFilter* rtabmap::Rtabmap::_bayesFilter
private

Definition at line 343 of file Rtabmap.h.

◆ _bufferedLogsF

std::list<std::string> rtabmap::Rtabmap::_bufferedLogsF
private

Definition at line 351 of file Rtabmap.h.

◆ _bufferedLogsI

std::list<std::string> rtabmap::Rtabmap::_bufferedLogsI
private

Definition at line 352 of file Rtabmap.h.

◆ _computeRMSE

bool rtabmap::Rtabmap::_computeRMSE
private

Definition at line 278 of file Rtabmap.h.

◆ _constraints

std::multimap<int, Link> rtabmap::Rtabmap::_constraints
private

Definition at line 359 of file Rtabmap.h.

◆ _createGlobalScanMap

bool rtabmap::Rtabmap::_createGlobalScanMap
private

Definition at line 328 of file Rtabmap.h.

◆ _currentSessionHasGPS

bool rtabmap::Rtabmap::_currentSessionHasGPS
private

Definition at line 365 of file Rtabmap.h.

◆ _databasePath

std::string rtabmap::Rtabmap::_databasePath
private

Definition at line 314 of file Rtabmap.h.

◆ _distanceTravelled

float rtabmap::Rtabmap::_distanceTravelled
private

Definition at line 336 of file Rtabmap.h.

◆ _distanceTravelledSinceLastLocalization

float rtabmap::Rtabmap::_distanceTravelledSinceLastLocalization
private

Definition at line 337 of file Rtabmap.h.

◆ _epipolarGeometry

EpipolarGeometry* rtabmap::Rtabmap::_epipolarGeometry
private

Definition at line 342 of file Rtabmap.h.

◆ _foutFloat

FILE* rtabmap::Rtabmap::_foutFloat
private

Definition at line 349 of file Rtabmap.h.

◆ _foutInt

FILE* rtabmap::Rtabmap::_foutInt
private

Definition at line 350 of file Rtabmap.h.

◆ _globalScanMap

LaserScan rtabmap::Rtabmap::_globalScanMap
private

Definition at line 366 of file Rtabmap.h.

◆ _globalScanMapPoses

std::map<int, Transform> rtabmap::Rtabmap::_globalScanMapPoses
private

Definition at line 367 of file Rtabmap.h.

◆ _goalReachedRadius

float rtabmap::Rtabmap::_goalReachedRadius
private

Definition at line 319 of file Rtabmap.h.

◆ _goalsSavedInUserData

bool rtabmap::Rtabmap::_goalsSavedInUserData
private

Definition at line 320 of file Rtabmap.h.

◆ _gpsGeocentricCache

std::map<int, std::pair<cv::Point3d, Transform> > rtabmap::Rtabmap::_gpsGeocentricCache
private

Definition at line 364 of file Rtabmap.h.

◆ _graphOptimizer

Optimizer* rtabmap::Rtabmap::_graphOptimizer
private

Definition at line 344 of file Rtabmap.h.

◆ _highestHypothesis

std::pair<int, float> rtabmap::Rtabmap::_highestHypothesis
private

Definition at line 333 of file Rtabmap.h.

◆ _lastLocalizationNodeId

int rtabmap::Rtabmap::_lastLocalizationNodeId
private

Definition at line 363 of file Rtabmap.h.

◆ _lastLocalizationPose

Transform rtabmap::Rtabmap::_lastLocalizationPose
private

Definition at line 362 of file Rtabmap.h.

◆ _lastProcessTime

double rtabmap::Rtabmap::_lastProcessTime
private

Definition at line 334 of file Rtabmap.h.

◆ _localImmunizationRatio

float rtabmap::Rtabmap::_localImmunizationRatio
private

Definition at line 305 of file Rtabmap.h.

◆ _localRadius

float rtabmap::Rtabmap::_localRadius
private

Definition at line 304 of file Rtabmap.h.

◆ _loopClosureHypothesis

std::pair<int, float> rtabmap::Rtabmap::_loopClosureHypothesis
private

Definition at line 332 of file Rtabmap.h.

◆ _loopClosureIdentityGuess

bool rtabmap::Rtabmap::_loopClosureIdentityGuess
private

Definition at line 303 of file Rtabmap.h.

◆ _loopCovLimited

bool rtabmap::Rtabmap::_loopCovLimited
private

Definition at line 325 of file Rtabmap.h.

◆ _loopGPS

bool rtabmap::Rtabmap::_loopGPS
private

Definition at line 326 of file Rtabmap.h.

◆ _loopRatio

float rtabmap::Rtabmap::_loopRatio
private

Definition at line 283 of file Rtabmap.h.

◆ _loopThr

float rtabmap::Rtabmap::_loopThr
private

Definition at line 282 of file Rtabmap.h.

◆ _mapCorrection

Transform rtabmap::Rtabmap::_mapCorrection
private

Definition at line 360 of file Rtabmap.h.

◆ _mapCorrectionBackup

Transform rtabmap::Rtabmap::_mapCorrectionBackup
private

Definition at line 361 of file Rtabmap.h.

◆ _markerPriors

std::map<int, Transform> rtabmap::Rtabmap::_markerPriors
private

Definition at line 371 of file Rtabmap.h.

◆ _markerPriorsAngularVariance

float rtabmap::Rtabmap::_markerPriorsAngularVariance
private

Definition at line 330 of file Rtabmap.h.

◆ _markerPriorsLinearVariance

float rtabmap::Rtabmap::_markerPriorsLinearVariance
private

Definition at line 329 of file Rtabmap.h.

◆ _maxLocalRetrieved

unsigned int rtabmap::Rtabmap::_maxLocalRetrieved
private

Definition at line 287 of file Rtabmap.h.

◆ _maxLoopClosureDistance

float rtabmap::Rtabmap::_maxLoopClosureDistance
private

Definition at line 284 of file Rtabmap.h.

◆ _maxMemoryAllowed

unsigned int rtabmap::Rtabmap::_maxMemoryAllowed
private

Definition at line 281 of file Rtabmap.h.

◆ _maxOdomCacheSize

int rtabmap::Rtabmap::_maxOdomCacheSize
private

Definition at line 327 of file Rtabmap.h.

◆ _maxRepublished

unsigned int rtabmap::Rtabmap::_maxRepublished
private

Definition at line 288 of file Rtabmap.h.

◆ _maxRetrieved

unsigned int rtabmap::Rtabmap::_maxRetrieved
private

Definition at line 286 of file Rtabmap.h.

◆ _maxTimeAllowed

float rtabmap::Rtabmap::_maxTimeAllowed
private

Definition at line 280 of file Rtabmap.h.

◆ _memory

Memory* rtabmap::Rtabmap::_memory
private

Definition at line 347 of file Rtabmap.h.

◆ _neighborLinkRefining

bool rtabmap::Rtabmap::_neighborLinkRefining
private

Definition at line 299 of file Rtabmap.h.

◆ _newMapOdomChangeDistance

float rtabmap::Rtabmap::_newMapOdomChangeDistance
private

Definition at line 298 of file Rtabmap.h.

◆ _nodesToRepublish

std::set<int> rtabmap::Rtabmap::_nodesToRepublish
private

Definition at line 373 of file Rtabmap.h.

◆ _odomCacheConstraints

std::multimap<int, Link> rtabmap::Rtabmap::_odomCacheConstraints
private

Definition at line 369 of file Rtabmap.h.

◆ _odomCachePoses

std::map<int, Transform> rtabmap::Rtabmap::_odomCachePoses
private

Definition at line 368 of file Rtabmap.h.

◆ _odomCorrectionAcc

std::vector<float> rtabmap::Rtabmap::_odomCorrectionAcc
private

Definition at line 370 of file Rtabmap.h.

◆ _optimizationMaxError

float rtabmap::Rtabmap::_optimizationMaxError
private

Definition at line 316 of file Rtabmap.h.

◆ _optimizedPoses

std::map<int, Transform> rtabmap::Rtabmap::_optimizedPoses
private

Definition at line 358 of file Rtabmap.h.

◆ _optimizeFromGraphEnd

bool rtabmap::Rtabmap::_optimizeFromGraphEnd
private

Definition at line 315 of file Rtabmap.h.

◆ _optimizeFromGraphEndChanged

bool rtabmap::Rtabmap::_optimizeFromGraphEndChanged
private

Definition at line 338 of file Rtabmap.h.

◆ _parameters

ParametersMap rtabmap::Rtabmap::_parameters
private

Definition at line 345 of file Rtabmap.h.

◆ _path

std::vector<std::pair<int,Transform> > rtabmap::Rtabmap::_path
private

Definition at line 377 of file Rtabmap.h.

◆ _pathAngularVelocity

float rtabmap::Rtabmap::_pathAngularVelocity
private

Definition at line 323 of file Rtabmap.h.

◆ _pathCurrentIndex

unsigned int rtabmap::Rtabmap::_pathCurrentIndex
private

Definition at line 379 of file Rtabmap.h.

◆ _pathGoalIndex

unsigned int rtabmap::Rtabmap::_pathGoalIndex
private

Definition at line 380 of file Rtabmap.h.

◆ _pathLinearVelocity

float rtabmap::Rtabmap::_pathLinearVelocity
private

Definition at line 322 of file Rtabmap.h.

◆ _pathStatus

int rtabmap::Rtabmap::_pathStatus
private

Definition at line 376 of file Rtabmap.h.

◆ _pathStuckCount

int rtabmap::Rtabmap::_pathStuckCount
private

Definition at line 382 of file Rtabmap.h.

◆ _pathStuckDistance

float rtabmap::Rtabmap::_pathStuckDistance
private

Definition at line 383 of file Rtabmap.h.

◆ _pathStuckIterations

int rtabmap::Rtabmap::_pathStuckIterations
private

Definition at line 321 of file Rtabmap.h.

◆ _pathTransformToGoal

Transform rtabmap::Rtabmap::_pathTransformToGoal
private

Definition at line 381 of file Rtabmap.h.

◆ _pathUnreachableNodes

std::set<unsigned int> rtabmap::Rtabmap::_pathUnreachableNodes
private

Definition at line 378 of file Rtabmap.h.

◆ _proximityAngle

float rtabmap::Rtabmap::_proximityAngle
private

Definition at line 311 of file Rtabmap.h.

◆ _proximityBySpace

bool rtabmap::Rtabmap::_proximityBySpace
private

Definition at line 301 of file Rtabmap.h.

◆ _proximityByTime

bool rtabmap::Rtabmap::_proximityByTime
private

Definition at line 300 of file Rtabmap.h.

◆ _proximityFilteringRadius

float rtabmap::Rtabmap::_proximityFilteringRadius
private

Definition at line 309 of file Rtabmap.h.

◆ _proximityMaxGraphDepth

int rtabmap::Rtabmap::_proximityMaxGraphDepth
private

Definition at line 306 of file Rtabmap.h.

◆ _proximityMaxNeighbors

int rtabmap::Rtabmap::_proximityMaxNeighbors
private

Definition at line 308 of file Rtabmap.h.

◆ _proximityMaxPaths

int rtabmap::Rtabmap::_proximityMaxPaths
private

Definition at line 307 of file Rtabmap.h.

◆ _proximityMergedScanCovFactor

double rtabmap::Rtabmap::_proximityMergedScanCovFactor
private

Definition at line 313 of file Rtabmap.h.

◆ _proximityOdomGuess

bool rtabmap::Rtabmap::_proximityOdomGuess
private

Definition at line 312 of file Rtabmap.h.

◆ _proximityRawPosesUsed

bool rtabmap::Rtabmap::_proximityRawPosesUsed
private

Definition at line 310 of file Rtabmap.h.

◆ _publishLastSignatureData

bool rtabmap::Rtabmap::_publishLastSignatureData
private

Definition at line 274 of file Rtabmap.h.

◆ _publishLikelihood

bool rtabmap::Rtabmap::_publishLikelihood
private

Definition at line 276 of file Rtabmap.h.

◆ _publishPdf

bool rtabmap::Rtabmap::_publishPdf
private

Definition at line 275 of file Rtabmap.h.

◆ _publishRAMUsage

bool rtabmap::Rtabmap::_publishRAMUsage
private

Definition at line 277 of file Rtabmap.h.

◆ _publishStats

bool rtabmap::Rtabmap::_publishStats
private

Definition at line 273 of file Rtabmap.h.

◆ _rawDataKept

bool rtabmap::Rtabmap::_rawDataKept
private

Definition at line 289 of file Rtabmap.h.

◆ _restartAtOrigin

bool rtabmap::Rtabmap::_restartAtOrigin
private

Definition at line 324 of file Rtabmap.h.

◆ _rgbdAngularSpeedUpdate

float rtabmap::Rtabmap::_rgbdAngularSpeedUpdate
private

Definition at line 297 of file Rtabmap.h.

◆ _rgbdAngularUpdate

float rtabmap::Rtabmap::_rgbdAngularUpdate
private

Definition at line 295 of file Rtabmap.h.

◆ _rgbdLinearSpeedUpdate

float rtabmap::Rtabmap::_rgbdLinearSpeedUpdate
private

Definition at line 296 of file Rtabmap.h.

◆ _rgbdLinearUpdate

float rtabmap::Rtabmap::_rgbdLinearUpdate
private

Definition at line 294 of file Rtabmap.h.

◆ _rgbdSlamMode

bool rtabmap::Rtabmap::_rgbdSlamMode
private

Definition at line 293 of file Rtabmap.h.

◆ _saveWMState

bool rtabmap::Rtabmap::_saveWMState
private

Definition at line 279 of file Rtabmap.h.

◆ _scanMatchingIdsSavedInLinks

bool rtabmap::Rtabmap::_scanMatchingIdsSavedInLinks
private

Definition at line 302 of file Rtabmap.h.

◆ _someNodesHaveBeenTransferred

bool rtabmap::Rtabmap::_someNodesHaveBeenTransferred
private

Definition at line 335 of file Rtabmap.h.

◆ _startNewMapOnGoodSignature

bool rtabmap::Rtabmap::_startNewMapOnGoodSignature
private

Definition at line 318 of file Rtabmap.h.

◆ _startNewMapOnLoopClosure

bool rtabmap::Rtabmap::_startNewMapOnLoopClosure
private

Definition at line 317 of file Rtabmap.h.

◆ _statisticLogged

bool rtabmap::Rtabmap::_statisticLogged
private

Definition at line 291 of file Rtabmap.h.

◆ _statisticLoggedHeaders

bool rtabmap::Rtabmap::_statisticLoggedHeaders
private

Definition at line 292 of file Rtabmap.h.

◆ _statisticLogsBufferedInRAM

bool rtabmap::Rtabmap::_statisticLogsBufferedInRAM
private

Definition at line 290 of file Rtabmap.h.

◆ _verifyLoopClosureHypothesis

bool rtabmap::Rtabmap::_verifyLoopClosureHypothesis
private

Definition at line 285 of file Rtabmap.h.

◆ _wDir

std::string rtabmap::Rtabmap::_wDir
private

Definition at line 356 of file Rtabmap.h.

◆ statistics_

Statistics rtabmap::Rtabmap::statistics_
private

Definition at line 354 of file Rtabmap.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:39:00