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)
bool computePath (int targetNode, bool global)
bool computePath (const Transform &targetPose)
int detectMoreLoopClosures (float clusterRadius=0.5f, float clusterAngle=M_PI/6.0f, int iterations=1)
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::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::list< std::map< int,
Transform > > 
getPaths (std::map< int, Transform > poses) 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 cv::Mat &image, int id=0)
bool process (const SensorData &data, const Transform &odomPose, const cv::Mat &covariance=cv::Mat::eye(6, 6, CV_64FC1))
void rejectLoopClosure (int oldId, int newId)
void resetMemory ()
 Rtabmap ()
std::pair< int, float > selectHypothesis (const std::map< int, float > &posterior, const std::map< int, float > &likelihood) const
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, 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, 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
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
unsigned int _maxLocalRetrieved
unsigned int _maxMemoryAllowed
unsigned int _maxRetrieved
float _maxTimeAllowed
Memory_memory
bool _neighborLinkRefining
float _newMapOdomChangeDistance
float _optimizationMaxLinearError
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
bool _proximityRawPosesUsed
bool _publishLastSignatureData
bool _publishLikelihood
bool _publishPdf
bool _publishStats
bool _rawDataKept
float _rgbdAngularUpdate
float _rgbdLinearUpdate
bool _rgbdSlamMode
bool _scanMatchingIdsSavedInLinks
bool _someNodesHaveBeenTransferred
bool _startNewMapOnLoopClosure
bool _statisticLogged
bool _statisticLoggedHeaders
bool _statisticLogsBufferedInRAM
std::string _wDir
Statistics statistics_

Detailed Description

Definition at line 52 of file Rtabmap.h.


Member Enumeration Documentation

Enumerator:
kVhNone 
kVhEpipolar 
kVhUndef 

Definition at line 55 of file Rtabmap.h.


Constructor & Destructor Documentation

Definition at line 75 of file Rtabmap.cpp.

Definition at line 136 of file Rtabmap.cpp.


Member Function Documentation

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

Definition at line 2980 of file Rtabmap.cpp.

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

Definition at line 3373 of file Rtabmap.cpp.

void rtabmap::Rtabmap::close ( bool  databaseSaved = true)

Definition at line 321 of file Rtabmap.cpp.

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

Definition at line 3391 of file Rtabmap.cpp.

bool rtabmap::Rtabmap::computePath ( const Transform targetPose)

Definition at line 3504 of file Rtabmap.cpp.

bool rtabmap::Rtabmap::computePath ( int  targetNode,
std::map< int, Transform nodes,
const std::multimap< int, rtabmap::Link > &  constraints 
) [private]
int rtabmap::Rtabmap::detectMoreLoopClosures ( float  clusterRadius = 0.5f,
float  clusterAngle = M_PI/6.0f,
int  iterations = 1 
)

Definition at line 3265 of file Rtabmap.cpp.

Definition at line 2687 of file Rtabmap.cpp.

Definition at line 3051 of file Rtabmap.cpp.

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

Definition at line 734 of file Rtabmap.cpp.

Definition at line 247 of file Rtabmap.cpp.

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

Definition at line 702 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 3109 of file Rtabmap.cpp.

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

Definition at line 2705 of file Rtabmap.cpp.

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

Definition at line 95 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 3190 of file Rtabmap.cpp.

Definition at line 76 of file Rtabmap.h.

Definition at line 77 of file Rtabmap.h.

Definition at line 97 of file Rtabmap.h.

Definition at line 494 of file Rtabmap.cpp.

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

Definition at line 85 of file Rtabmap.h.

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

Definition at line 91 of file Rtabmap.h.

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

Definition at line 96 of file Rtabmap.h.

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

Definition at line 74 of file Rtabmap.h.

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

Definition at line 75 of file Rtabmap.h.

Definition at line 93 of file Rtabmap.h.

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

Definition at line 94 of file Rtabmap.h.

Definition at line 116 of file Rtabmap.h.

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

Definition at line 136 of file Rtabmap.h.

Definition at line 3670 of file Rtabmap.cpp.

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

Definition at line 141 of file Rtabmap.h.

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

Definition at line 140 of file Rtabmap.h.

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

Definition at line 3645 of file Rtabmap.cpp.

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

Definition at line 3620 of file Rtabmap.cpp.

std::list< std::map< int, Transform > > rtabmap::Rtabmap::getPaths ( std::map< int, Transform poses) const

Definition at line 2821 of file Rtabmap.cpp.

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

Definition at line 132 of file Rtabmap.h.

Definition at line 142 of file Rtabmap.h.

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

Definition at line 620 of file Rtabmap.cpp.

Definition at line 597 of file Rtabmap.cpp.

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

Definition at line 535 of file Rtabmap.cpp.

Definition at line 544 of file Rtabmap.cpp.

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

Definition at line 99 of file Rtabmap.h.

Definition at line 553 of file Rtabmap.cpp.

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

Definition at line 524 of file Rtabmap.cpp.

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

Definition at line 504 of file Rtabmap.cpp.

Definition at line 515 of file Rtabmap.cpp.

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

Definition at line 566 of file Rtabmap.cpp.

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

Definition at line 72 of file Rtabmap.h.

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

Definition at line 269 of file Rtabmap.cpp.

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

Definition at line 307 of file Rtabmap.cpp.

Definition at line 588 of file Rtabmap.cpp.

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

Definition at line 579 of file Rtabmap.cpp.

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

Definition at line 73 of file Rtabmap.h.

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

Definition at line 662 of file Rtabmap.cpp.

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

Definition at line 2850 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,
std::multimap< int, Link > *  constraints = 0,
double *  error = 0,
int *  iterationsDone = 0 
) const [private]

Definition at line 2895 of file Rtabmap.cpp.

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

Definition at line 374 of file Rtabmap.cpp.

bool rtabmap::Rtabmap::process ( const cv::Mat &  image,
int  id = 0 
)

Definition at line 2614 of file Rtabmap.cpp.

bool rtabmap::Rtabmap::process ( const SensorData data,
const Transform odomPose,
const cv::Mat &  covariance = cv::Mat::eye(6,6,CV_64FC1) 
)

Definition at line 805 of file Rtabmap.cpp.

void rtabmap::Rtabmap::rejectLoopClosure ( int  oldId,
int  newId 
)

Definition at line 2664 of file Rtabmap.cpp.

Definition at line 769 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::setOptimizedPoses ( const std::map< int, Transform > &  poses)

Definition at line 2682 of file Rtabmap.cpp.

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

Definition at line 2620 of file Rtabmap.cpp.

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

Definition at line 141 of file Rtabmap.cpp.

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

Definition at line 682 of file Rtabmap.cpp.

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

Definition at line 2635 of file Rtabmap.cpp.

Definition at line 633 of file Rtabmap.cpp.

Definition at line 3680 of file Rtabmap.cpp.


Member Data Documentation

Definition at line 220 of file Rtabmap.h.

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

Definition at line 228 of file Rtabmap.h.

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

Definition at line 229 of file Rtabmap.h.

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

Definition at line 236 of file Rtabmap.h.

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

Definition at line 201 of file Rtabmap.h.

Definition at line 215 of file Rtabmap.h.

Definition at line 219 of file Rtabmap.h.

Definition at line 226 of file Rtabmap.h.

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

Definition at line 227 of file Rtabmap.h.

Definition at line 205 of file Rtabmap.h.

Definition at line 206 of file Rtabmap.h.

Definition at line 221 of file Rtabmap.h.

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

Definition at line 212 of file Rtabmap.h.

Definition at line 239 of file Rtabmap.h.

Definition at line 238 of file Rtabmap.h.

Definition at line 213 of file Rtabmap.h.

Definition at line 196 of file Rtabmap.h.

Definition at line 195 of file Rtabmap.h.

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

Definition at line 211 of file Rtabmap.h.

Definition at line 180 of file Rtabmap.h.

float rtabmap::Rtabmap::_loopThr [private]

Definition at line 179 of file Rtabmap.h.

Definition at line 237 of file Rtabmap.h.

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

Definition at line 182 of file Rtabmap.h.

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

Definition at line 178 of file Rtabmap.h.

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

Definition at line 181 of file Rtabmap.h.

Definition at line 177 of file Rtabmap.h.

Definition at line 224 of file Rtabmap.h.

Definition at line 191 of file Rtabmap.h.

Definition at line 190 of file Rtabmap.h.

Definition at line 203 of file Rtabmap.h.

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

Definition at line 235 of file Rtabmap.h.

Definition at line 202 of file Rtabmap.h.

Definition at line 222 of file Rtabmap.h.

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

Definition at line 243 of file Rtabmap.h.

Definition at line 209 of file Rtabmap.h.

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

Definition at line 245 of file Rtabmap.h.

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

Definition at line 246 of file Rtabmap.h.

Definition at line 208 of file Rtabmap.h.

Definition at line 242 of file Rtabmap.h.

Definition at line 248 of file Rtabmap.h.

Definition at line 249 of file Rtabmap.h.

Definition at line 207 of file Rtabmap.h.

Definition at line 247 of file Rtabmap.h.

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

Definition at line 244 of file Rtabmap.h.

Definition at line 200 of file Rtabmap.h.

Definition at line 193 of file Rtabmap.h.

Definition at line 192 of file Rtabmap.h.

Definition at line 198 of file Rtabmap.h.

Definition at line 197 of file Rtabmap.h.

Definition at line 199 of file Rtabmap.h.

Definition at line 174 of file Rtabmap.h.

Definition at line 176 of file Rtabmap.h.

Definition at line 175 of file Rtabmap.h.

Definition at line 173 of file Rtabmap.h.

Definition at line 183 of file Rtabmap.h.

Definition at line 189 of file Rtabmap.h.

Definition at line 188 of file Rtabmap.h.

Definition at line 187 of file Rtabmap.h.

Definition at line 194 of file Rtabmap.h.

Definition at line 214 of file Rtabmap.h.

Definition at line 204 of file Rtabmap.h.

Definition at line 185 of file Rtabmap.h.

Definition at line 186 of file Rtabmap.h.

Definition at line 184 of file Rtabmap.h.

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

Definition at line 233 of file Rtabmap.h.

Definition at line 231 of file Rtabmap.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:32