#include <Rtabmap.h>
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, Transform > | getForwardWMPoses (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 Transform & | getLastLocalizationPose () 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 Memory * | getMemory () const |
| const ParametersMap & | getParameters () 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 Transform & | getPathTransformToGoal () const |
| Transform | getPose (int locationId) const |
| const Statistics & | getStatistics () 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 ¶meters, 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 ¶meters) |
| 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, Transform > | 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 |
| 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_ |
Definition at line 75 of file Rtabmap.cpp.
| rtabmap::Rtabmap::~Rtabmap | ( | ) | [virtual] |
Definition at line 136 of file Rtabmap.cpp.
| 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.
| void rtabmap::Rtabmap::dumpData | ( | ) | const |
Definition at line 2687 of file Rtabmap.cpp.
| void rtabmap::Rtabmap::dumpPrediction | ( | ) | const |
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.
| void rtabmap::Rtabmap::flushStatisticLogs | ( | ) | [private] |
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] |
| 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.
| int rtabmap::Rtabmap::getHighestHypothesisId | ( | ) | const [inline] |
| float rtabmap::Rtabmap::getHighestHypothesisValue | ( | ) | const [inline] |
| const Transform& rtabmap::Rtabmap::getLastLocalizationPose | ( | ) | const [inline] |
| int rtabmap::Rtabmap::getLastLocationId | ( | ) | const |
Definition at line 494 of file Rtabmap.cpp.
| double rtabmap::Rtabmap::getLastProcessTime | ( | ) | const [inline] |
| const std::map<int, Transform>& rtabmap::Rtabmap::getLocalOptimizedPoses | ( | ) | const [inline] |
| float rtabmap::Rtabmap::getLocalRadius | ( | ) | const [inline] |
| int rtabmap::Rtabmap::getLoopClosureId | ( | ) | const [inline] |
| float rtabmap::Rtabmap::getLoopClosureValue | ( | ) | const [inline] |
| Transform rtabmap::Rtabmap::getMapCorrection | ( | ) | const [inline] |
| const Memory* rtabmap::Rtabmap::getMemory | ( | ) | const [inline] |
| const ParametersMap& rtabmap::Rtabmap::getParameters | ( | ) | const [inline] |
| const std::vector<std::pair<int, Transform> >& rtabmap::Rtabmap::getPath | ( | ) | const [inline] |
| int rtabmap::Rtabmap::getPathCurrentGoalId | ( | ) | const |
Definition at line 3670 of file Rtabmap.cpp.
| unsigned int rtabmap::Rtabmap::getPathCurrentGoalIndex | ( | ) | const [inline] |
| unsigned int rtabmap::Rtabmap::getPathCurrentIndex | ( | ) | const [inline] |
| 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] |
| const Transform& rtabmap::Rtabmap::getPathTransformToGoal | ( | ) | const [inline] |
| Transform rtabmap::Rtabmap::getPose | ( | int | locationId | ) | const |
Definition at line 620 of file Rtabmap.cpp.
| const Statistics & rtabmap::Rtabmap::getStatistics | ( | ) | const |
Definition at line 597 of file Rtabmap.cpp.
| std::set< int > rtabmap::Rtabmap::getSTM | ( | ) | const |
Definition at line 535 of file Rtabmap.cpp.
| int rtabmap::Rtabmap::getSTMSize | ( | ) | const |
Definition at line 544 of file Rtabmap.cpp.
| float rtabmap::Rtabmap::getTimeThreshold | ( | ) | const [inline] |
| int rtabmap::Rtabmap::getTotalMemSize | ( | ) | const |
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.
| int rtabmap::Rtabmap::getWMSize | ( | ) | const |
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] |
| 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.
| bool rtabmap::Rtabmap::isIDsGenerated | ( | ) | const |
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] |
| 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.
| void rtabmap::Rtabmap::resetMemory | ( | ) |
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.
| int rtabmap::Rtabmap::triggerNewMap | ( | ) |
Definition at line 633 of file Rtabmap.cpp.
| void rtabmap::Rtabmap::updateGoalIndex | ( | ) | [private] |
Definition at line 3680 of file Rtabmap.cpp.
BayesFilter* rtabmap::Rtabmap::_bayesFilter [private] |
std::list<std::string> rtabmap::Rtabmap::_bufferedLogsF [private] |
std::list<std::string> rtabmap::Rtabmap::_bufferedLogsI [private] |
std::multimap<int, Link> rtabmap::Rtabmap::_constraints [private] |
std::string rtabmap::Rtabmap::_databasePath [private] |
float rtabmap::Rtabmap::_distanceTravelled [private] |
FILE* rtabmap::Rtabmap::_foutFloat [private] |
FILE* rtabmap::Rtabmap::_foutInt [private] |
float rtabmap::Rtabmap::_goalReachedRadius [private] |
bool rtabmap::Rtabmap::_goalsSavedInUserData [private] |
Optimizer* rtabmap::Rtabmap::_graphOptimizer [private] |
std::pair<int, float> rtabmap::Rtabmap::_highestHypothesis [private] |
int rtabmap::Rtabmap::_lastLocalizationNodeId [private] |
double rtabmap::Rtabmap::_lastProcessTime [private] |
float rtabmap::Rtabmap::_localImmunizationRatio [private] |
float rtabmap::Rtabmap::_localRadius [private] |
std::pair<int, float> rtabmap::Rtabmap::_loopClosureHypothesis [private] |
float rtabmap::Rtabmap::_loopRatio [private] |
float rtabmap::Rtabmap::_loopThr [private] |
Transform rtabmap::Rtabmap::_mapCorrection [private] |
unsigned int rtabmap::Rtabmap::_maxLocalRetrieved [private] |
unsigned int rtabmap::Rtabmap::_maxMemoryAllowed [private] |
unsigned int rtabmap::Rtabmap::_maxRetrieved [private] |
float rtabmap::Rtabmap::_maxTimeAllowed [private] |
Memory* rtabmap::Rtabmap::_memory [private] |
bool rtabmap::Rtabmap::_neighborLinkRefining [private] |
float rtabmap::Rtabmap::_newMapOdomChangeDistance [private] |
float rtabmap::Rtabmap::_optimizationMaxLinearError [private] |
std::map<int, Transform> rtabmap::Rtabmap::_optimizedPoses [private] |
bool rtabmap::Rtabmap::_optimizeFromGraphEnd [private] |
ParametersMap rtabmap::Rtabmap::_parameters [private] |
std::vector<std::pair<int,Transform> > rtabmap::Rtabmap::_path [private] |
float rtabmap::Rtabmap::_pathAngularVelocity [private] |
unsigned int rtabmap::Rtabmap::_pathCurrentIndex [private] |
unsigned int rtabmap::Rtabmap::_pathGoalIndex [private] |
float rtabmap::Rtabmap::_pathLinearVelocity [private] |
int rtabmap::Rtabmap::_pathStatus [private] |
int rtabmap::Rtabmap::_pathStuckCount [private] |
float rtabmap::Rtabmap::_pathStuckDistance [private] |
int rtabmap::Rtabmap::_pathStuckIterations [private] |
std::set<unsigned int> rtabmap::Rtabmap::_pathUnreachableNodes [private] |
float rtabmap::Rtabmap::_proximityAngle [private] |
bool rtabmap::Rtabmap::_proximityBySpace [private] |
bool rtabmap::Rtabmap::_proximityByTime [private] |
float rtabmap::Rtabmap::_proximityFilteringRadius [private] |
int rtabmap::Rtabmap::_proximityMaxGraphDepth [private] |
bool rtabmap::Rtabmap::_proximityRawPosesUsed [private] |
bool rtabmap::Rtabmap::_publishLastSignatureData [private] |
bool rtabmap::Rtabmap::_publishLikelihood [private] |
bool rtabmap::Rtabmap::_publishPdf [private] |
bool rtabmap::Rtabmap::_publishStats [private] |
bool rtabmap::Rtabmap::_rawDataKept [private] |
float rtabmap::Rtabmap::_rgbdAngularUpdate [private] |
float rtabmap::Rtabmap::_rgbdLinearUpdate [private] |
bool rtabmap::Rtabmap::_rgbdSlamMode [private] |
bool rtabmap::Rtabmap::_scanMatchingIdsSavedInLinks [private] |
bool rtabmap::Rtabmap::_someNodesHaveBeenTransferred [private] |
bool rtabmap::Rtabmap::_startNewMapOnLoopClosure [private] |
bool rtabmap::Rtabmap::_statisticLogged [private] |
bool rtabmap::Rtabmap::_statisticLoggedHeaders [private] |
bool rtabmap::Rtabmap::_statisticLogsBufferedInRAM [private] |
std::string rtabmap::Rtabmap::_wDir [private] |
Statistics rtabmap::Rtabmap::statistics_ [private] |