Public Types | Public Member Functions | Private Member Functions | Private Attributes
rtabmap::Rtabmap Class Reference

#include <Rtabmap.h>

List of all members.

Public Types

enum  VhStrategy { kVhNone, kVhEpipolar, kVhUndef }

Public Member Functions

void adjustLikelihood (std::map< int, float > &likelihood) const
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 clusterRadius=0.5f, float clusterAngle=M_PI/6.0f, int iterations=1, const ProgressState *state=0)
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)
void get3DMap (std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const
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)
int getHighestHypothesisId () const
float getHighestHypothesisValue () 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
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 (std::map< int, Transform > poses, const Transform &target, int maxGraphDepth=0) const
int getPathStatus () const
const TransformgetPathTransformToGoal () const
Transform getPose (int locationId) 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
std::multimap< int, cv::KeyPoint > getWords (int locationId) const
const std::string & getWorkingDir () const
void init (const ParametersMap &parameters, const std::string &databasePath="")
void init (const std::string &configFile="", const std::string &databasePath="")
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.
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 ()
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)
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 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
std::string _databasePath
float _distanceTravelled
EpipolarGeometry_epipolarGeometry
FILE * _foutFloat
FILE * _foutInt
float _goalReachedRadius
bool _goalsSavedInUserData
Optimizer_graphOptimizer
std::pair< int, float > _highestHypothesis
int _lastLocalizationNodeId
Transform _lastLocalizationPose
double _lastProcessTime
float _localImmunizationRatio
float _localRadius
std::pair< int, float > _loopClosureHypothesis
float _loopRatio
float _loopThr
Transform _mapCorrection
Transform _mapCorrectionBackup
unsigned int _maxLocalRetrieved
unsigned int _maxMemoryAllowed
unsigned int _maxRetrieved
float _maxTimeAllowed
Memory_memory
bool _neighborLinkRefining
float _newMapOdomChangeDistance
float _optimizationMaxError
std::map< int, Transform_optimizedPoses
bool _optimizeFromGraphEnd
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
bool _proximityRawPosesUsed
bool _publishLastSignatureData
bool _publishLikelihood
bool _publishPdf
bool _publishRAMUsage
bool _publishStats
bool _rawDataKept
float _rgbdAngularSpeedUpdate
float _rgbdAngularUpdate
float _rgbdLinearSpeedUpdate
float _rgbdLinearUpdate
bool _rgbdSlamMode
bool _savedLocalizationIgnored
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 53 of file Rtabmap.h.


Member Enumeration Documentation

Enumerator:
kVhNone 
kVhEpipolar 
kVhUndef 

Definition at line 56 of file Rtabmap.h.


Constructor & Destructor Documentation

Definition at line 78 of file Rtabmap.cpp.

Definition at line 149 of file Rtabmap.cpp.


Member Function Documentation

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

Definition at line 3541 of file Rtabmap.cpp.

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

Definition at line 4139 of file Rtabmap.cpp.

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 348 of file Rtabmap.cpp.

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

Definition at line 4157 of file Rtabmap.cpp.

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

Definition at line 4274 of file Rtabmap.cpp.

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

Definition at line 3126 of file Rtabmap.cpp.

int rtabmap::Rtabmap::detectMoreLoopClosures ( float  clusterRadius = 0.5f,
float  clusterAngle = M_PI/6.0f,
int  iterations = 1,
const ProgressState state = 0 
)

Definition at line 3843 of file Rtabmap.cpp.

Definition at line 3181 of file Rtabmap.cpp.

Definition at line 3612 of file Rtabmap.cpp.

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

Definition at line 791 of file Rtabmap.cpp.

Definition at line 260 of file Rtabmap.cpp.

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

Definition at line 759 of file Rtabmap.cpp.

void rtabmap::Rtabmap::get3DMap ( std::map< int, Signature > &  signatures,
std::map< int, Transform > &  poses,
std::multimap< int, Link > &  constraints,
bool  optimized,
bool  global 
) const

Definition at line 3670 of file Rtabmap.cpp.

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

Definition at line 3199 of file Rtabmap.cpp.

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

Definition at line 125 of file Rtabmap.h.

void rtabmap::Rtabmap::getGraph ( std::map< int, Transform > &  poses,
std::multimap< int, Link > &  constraints,
bool  optimized,
bool  global,
std::map< int, Signature > *  signatures = 0 
)

Definition at line 3759 of file Rtabmap.cpp.

Definition at line 105 of file Rtabmap.h.

Definition at line 106 of file Rtabmap.h.

Definition at line 127 of file Rtabmap.h.

Definition at line 528 of file Rtabmap.cpp.

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

Definition at line 114 of file Rtabmap.h.

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

Definition at line 121 of file Rtabmap.h.

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

Definition at line 120 of file Rtabmap.h.

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

Definition at line 126 of file Rtabmap.h.

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

Definition at line 103 of file Rtabmap.h.

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

Definition at line 104 of file Rtabmap.h.

Definition at line 123 of file Rtabmap.h.

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

Definition at line 124 of file Rtabmap.h.

Definition at line 154 of file Rtabmap.h.

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

Definition at line 176 of file Rtabmap.h.

Definition at line 4445 of file Rtabmap.cpp.

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

Definition at line 181 of file Rtabmap.h.

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

Definition at line 180 of file Rtabmap.h.

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

Definition at line 4420 of file Rtabmap.cpp.

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

Definition at line 4395 of file Rtabmap.cpp.

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

Definition at line 3315 of file Rtabmap.cpp.

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

Definition at line 172 of file Rtabmap.h.

Definition at line 182 of file Rtabmap.h.

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

Definition at line 654 of file Rtabmap.cpp.

Definition at line 631 of file Rtabmap.cpp.

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

Definition at line 569 of file Rtabmap.cpp.

Definition at line 578 of file Rtabmap.cpp.

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

Definition at line 129 of file Rtabmap.h.

Definition at line 587 of file Rtabmap.cpp.

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

Definition at line 558 of file Rtabmap.cpp.

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

Definition at line 538 of file Rtabmap.cpp.

Definition at line 549 of file Rtabmap.cpp.

std::multimap< int, cv::KeyPoint > rtabmap::Rtabmap::getWords ( int  locationId) const

Definition at line 600 of file Rtabmap.cpp.

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

Definition at line 101 of file Rtabmap.h.

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

Definition at line 282 of file Rtabmap.cpp.

void rtabmap::Rtabmap::init ( const std::string &  configFile = "",
const std::string &  databasePath = "" 
)

Definition at line 334 of file Rtabmap.cpp.

Definition at line 622 of file Rtabmap.cpp.

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

Definition at line 613 of file Rtabmap.cpp.

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

Definition at line 102 of file Rtabmap.h.

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

Definition at line 719 of file Rtabmap.cpp.

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 3378 of file Rtabmap.cpp.

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 3424 of file Rtabmap.cpp.

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

Definition at line 405 of file Rtabmap.cpp.

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 897 of file Rtabmap.cpp.

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 875 of file Rtabmap.cpp.

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 868 of file Rtabmap.cpp.

Definition at line 4093 of file Rtabmap.cpp.

Definition at line 3068 of file Rtabmap.cpp.

Definition at line 829 of file Rtabmap.cpp.

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

Definition at line 667 of file Rtabmap.cpp.

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

Definition at line 3176 of file Rtabmap.cpp.

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

Definition at line 3026 of file Rtabmap.cpp.

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

Definition at line 154 of file Rtabmap.cpp.

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 739 of file Rtabmap.cpp.

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

Definition at line 3041 of file Rtabmap.cpp.

Definition at line 685 of file Rtabmap.cpp.

Definition at line 4455 of file Rtabmap.cpp.


Member Data Documentation

Definition at line 272 of file Rtabmap.h.

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

Definition at line 280 of file Rtabmap.h.

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

Definition at line 281 of file Rtabmap.h.

Definition at line 220 of file Rtabmap.h.

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

Definition at line 288 of file Rtabmap.h.

std::string rtabmap::Rtabmap::_databasePath [private]

Definition at line 251 of file Rtabmap.h.

Definition at line 267 of file Rtabmap.h.

Definition at line 271 of file Rtabmap.h.

Definition at line 278 of file Rtabmap.h.

FILE* rtabmap::Rtabmap::_foutInt [private]

Definition at line 279 of file Rtabmap.h.

Definition at line 256 of file Rtabmap.h.

Definition at line 257 of file Rtabmap.h.

Definition at line 273 of file Rtabmap.h.

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

Definition at line 264 of file Rtabmap.h.

Definition at line 292 of file Rtabmap.h.

Definition at line 291 of file Rtabmap.h.

Definition at line 265 of file Rtabmap.h.

Definition at line 244 of file Rtabmap.h.

Definition at line 243 of file Rtabmap.h.

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

Definition at line 263 of file Rtabmap.h.

Definition at line 225 of file Rtabmap.h.

float rtabmap::Rtabmap::_loopThr [private]

Definition at line 224 of file Rtabmap.h.

Definition at line 289 of file Rtabmap.h.

Definition at line 290 of file Rtabmap.h.

unsigned int rtabmap::Rtabmap::_maxLocalRetrieved [private]

Definition at line 228 of file Rtabmap.h.

unsigned int rtabmap::Rtabmap::_maxMemoryAllowed [private]

Definition at line 223 of file Rtabmap.h.

unsigned int rtabmap::Rtabmap::_maxRetrieved [private]

Definition at line 227 of file Rtabmap.h.

Definition at line 222 of file Rtabmap.h.

Definition at line 276 of file Rtabmap.h.

Definition at line 239 of file Rtabmap.h.

Definition at line 238 of file Rtabmap.h.

Definition at line 253 of file Rtabmap.h.

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

Definition at line 287 of file Rtabmap.h.

Definition at line 252 of file Rtabmap.h.

Definition at line 274 of file Rtabmap.h.

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

Definition at line 296 of file Rtabmap.h.

Definition at line 260 of file Rtabmap.h.

unsigned int rtabmap::Rtabmap::_pathCurrentIndex [private]

Definition at line 298 of file Rtabmap.h.

unsigned int rtabmap::Rtabmap::_pathGoalIndex [private]

Definition at line 299 of file Rtabmap.h.

Definition at line 259 of file Rtabmap.h.

Definition at line 295 of file Rtabmap.h.

Definition at line 301 of file Rtabmap.h.

Definition at line 302 of file Rtabmap.h.

Definition at line 258 of file Rtabmap.h.

Definition at line 300 of file Rtabmap.h.

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

Definition at line 297 of file Rtabmap.h.

Definition at line 250 of file Rtabmap.h.

Definition at line 241 of file Rtabmap.h.

Definition at line 240 of file Rtabmap.h.

Definition at line 248 of file Rtabmap.h.

Definition at line 245 of file Rtabmap.h.

Definition at line 247 of file Rtabmap.h.

Definition at line 246 of file Rtabmap.h.

Definition at line 249 of file Rtabmap.h.

Definition at line 216 of file Rtabmap.h.

Definition at line 218 of file Rtabmap.h.

Definition at line 217 of file Rtabmap.h.

Definition at line 219 of file Rtabmap.h.

Definition at line 215 of file Rtabmap.h.

Definition at line 229 of file Rtabmap.h.

Definition at line 237 of file Rtabmap.h.

Definition at line 235 of file Rtabmap.h.

Definition at line 236 of file Rtabmap.h.

Definition at line 234 of file Rtabmap.h.

Definition at line 233 of file Rtabmap.h.

Definition at line 261 of file Rtabmap.h.

Definition at line 221 of file Rtabmap.h.

Definition at line 242 of file Rtabmap.h.

Definition at line 266 of file Rtabmap.h.

Definition at line 255 of file Rtabmap.h.

Definition at line 254 of file Rtabmap.h.

Definition at line 231 of file Rtabmap.h.

Definition at line 232 of file Rtabmap.h.

Definition at line 230 of file Rtabmap.h.

Definition at line 226 of file Rtabmap.h.

std::string rtabmap::Rtabmap::_wDir [private]

Definition at line 285 of file Rtabmap.h.

Definition at line 283 of file Rtabmap.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:42