Public Member Functions | Static Public Attributes | Protected Attributes | Private Member Functions | Private Attributes
rtabmap::Memory Class Reference

#include <Memory.h>

List of all members.

Public Member Functions

bool addLink (int to, int from, const Transform &transform, Link::Type type, float rotVariance, float transVariance)
std::list< int > cleanup (const std::list< int > &ignoredIds=std::list< int >())
Transform computeIcpTransform (int oldId, int newId, Transform guess, bool icp3D, std::string *rejectedMsg=0, int *correspondences=0, double *variance=0, float *correspondencesRatio=0)
Transform computeIcpTransform (const Signature &oldS, const Signature &newS, Transform guess, bool icp3D, std::string *rejectedMsg=0, int *correspondences=0, double *variance=0, float *correspondencesRatio=0) const
std::map< int, float > computeLikelihood (const Signature *signature, const std::list< int > &ids)
Transform computeScanMatchingTransform (int newId, int oldId, const std::map< int, Transform > &poses, std::string *rejectedMsg=0, int *inliers=0, double *variance=0)
Transform computeVisualTransform (int oldId, int newId, std::string *rejectedMsg=0, int *inliers=0, double *variance=0) const
Transform computeVisualTransform (const Signature &oldS, const Signature &newS, std::string *rejectedMsg=0, int *inliers=0, double *variance=0) const
void createGraph (GraphNode *parent, unsigned int maxDepth, const std::set< int > &endIds=std::set< int >())
void deleteLocation (int locationId, std::list< int > *deletedWords=0)
void dumpDictionary (const char *fileNameRef, const char *fileNameDesc) const
virtual void dumpMemory (std::string directory) const
void dumpMemoryTree (const char *fileNameTree) const
virtual void dumpSignatures (const char *fileNameSign, bool words3D) const
void emptyTrash ()
std::list< int > forget (const std::set< int > &ignoredIds=std::set< int >())
void generateGraph (const std::string &fileName, std::set< int > ids=std::set< int >())
std::map< int, std::string > getAllLabels () const
std::set< int > getAllSignatureIds () const
bool getBowForce2D () const
float getBowInlierDistance () const
int getBowIterations () const
float getBowMaxDepth () const
int getBowMinInliers () const
int getDatabaseMemoryUsed () const
double getDbSavingTime () const
const Feature2DgetFeature2D () const
Feature2D::Type getFeatureType () const
cv::Mat getImageCompressed (int signatureId) const
int getLastGlobalLoopClosureId () const
int getLastSignatureId () const
const SignaturegetLastWorkingSignature () const
std::map< int, LinkgetLoopClosureLinks (int signatureId, bool lookInDatabase=false) const
int getMaxStMemSize () const
void getMetricConstraints (const std::set< int > &ids, std::map< int, Transform > &poses, std::multimap< int, Link > &links, bool lookInDatabase=false)
std::map< int, LinkgetNeighborLinks (int signatureId, bool lookInDatabase=false) const
std::map< int, int > getNeighborsId (int signatureId, int maxGraphDepth, int maxCheckedInDatabase=-1, bool incrementMarginOnLoop=false, bool ignoreLoopIds=false, double *dbAccessTime=0) const
std::map< int, float > getNeighborsIdRadius (int signatureId, float radius, const std::map< int, Transform > &optimizedPoses, int maxGraphDepth) const
bool getNodeInfo (int signatureId, Transform &odomPose, int &mapId, int &weight, std::string &label, double &stamp, std::vector< unsigned char > &userData, bool lookInDatabase=false) const
Transform getOdomPose (int signatureId, bool lookInDatabase=false) const
const SignaturegetSignature (int id) const
Signature getSignatureData (int locationId, bool uncompressedData=false)
Signature getSignatureDataConst (int locationId) const
int getSignatureIdByLabel (const std::string &label, bool lookInDatabase=true) const
float getSimilarityThreshold () const
const std::set< int > & getStMem () const
const VWDictionarygetVWDictionary () const
std::map< int, int > getWeights () const
const std::map< int, double > & getWorkingMem () const
int incrementMapId ()
bool init (const std::string &dbUrl, bool dbOverwritten=false, const ParametersMap &parameters=ParametersMap(), bool postInitClosingEvents=false)
bool isBinDataKept () const
bool isIDsGenerated () const
bool isIncremental () const
bool isInLTM (int signatureId) const
bool isInSTM (int signatureId) const
bool isInWM (int signatureId) const
bool isRawDataKept () const
void joinTrashThread ()
bool labelSignature (int id, const std::string &label)
 Memory (const ParametersMap &parameters=ParametersMap())
bool memoryChanged () const
virtual void parseParameters (const ParametersMap &parameters)
std::set< int > reactivateSignatures (const std::list< int > &ids, unsigned int maxLoaded, double &timeDbAccess)
void removeAllVirtualLinks ()
void removeLink (int idA, int idB)
void setRoi (const std::string &roi)
bool setUserData (int id, const std::vector< unsigned char > &data)
bool update (const SensorData &data, Statistics *stats=0)
void updateAge (int signatureId)
void updateLink (int fromId, int toId, const Transform &transform, float rotVariance, float transVariance)
virtual ~Memory ()

Static Public Attributes

static const int kIdInvalid = 0
static const int kIdStart = 0
static const int kIdVirtual = -1

Protected Attributes

DBDriver_dbDriver

Private Member Functions

Signature_getSignature (int id) const
void addSignatureToStm (Signature *signature, float poseRotVariance, float poseTransVariance)
void addSignatureToWm (Signature *signature)
void cleanUnusedWords ()
void clear ()
void copyData (const Signature *from, Signature *to)
SignaturecreateSignature (const SensorData &data, Statistics *stats=0)
void disableWordsRef (int signatureId)
void enableWordsRef (const std::list< int > &signatureIds)
int getNextId ()
int getNi (int signatureId) const
std::list< Signature * > getRemovableSignatures (int count, const std::set< int > &ignoredIds=std::set< int >())
const std::map< int, Signature * > & getSignatures () const
void initCountId ()
void moveToTrash (Signature *s, bool keepLinkedToGraph=true, std::list< int > *deletedWords=0)
void preUpdate ()
void rehearsal (Signature *signature, Statistics *stats=0)
bool rehearsalMerge (int oldId, int newId)

Private Attributes

bool _badSignaturesIgnored
float _badSignRatio
bool _binDataKept
bool _bowEpipolarGeometry
float _bowEpipolarGeometryVar
bool _bowForce2D
float _bowInlierDistance
int _bowIterations
float _bowMaxDepth
int _bowMinInliers
Feature2D_feature2D
Feature2D::Type _featureType
bool _generateIds
float _icp2CorrespondenceRatio
float _icp2MaxCorrespondenceDistance
int _icp2MaxIterations
float _icp2VoxelSize
float _icpCorrespondenceRatio
int _icpDecimation
float _icpMaxCorrespondenceDistance
float _icpMaxDepth
int _icpMaxIterations
float _icpMaxRotation
float _icpMaxTranslation
bool _icpPointToPlane
int _icpPointToPlaneNormalNeighbors
int _icpSamples
float _icpVoxelSize
int _idCount
int _idMapCount
bool _idUpdatedToNewOneRehearsal
int _imageDecimation
bool _incrementalMemory
float _laserScanVoxelSize
int _lastGlobalLoopClosureId
Signature_lastSignature
bool _linksChanged
bool _localSpaceLinksKeptInWM
int _maxStMemSize
bool _memoryChanged
bool _notLinkedNodesKeptInDb
bool _parallelized
bool _postInitClosingEvents
bool _rawDataKept
float _recentWmRatio
float _rehearsalMaxAngle
float _rehearsalMaxDistance
bool _rehearsalWeightIgnoredWhileMoving
std::vector< float > _roiRatios
std::map< int, Signature * > _signatures
int _signaturesAdded
float _similarityThreshold
double _stereoFlowEpsilon
int _stereoFlowIterations
int _stereoFlowMaxLevel
int _stereoFlowWinSize
float _stereoMaxSlope
std::set< int > _stMem
double _subPixEps
int _subPixIterations
int _subPixWinSize
bool _tfIdfLikelihoodUsed
bool _transferSortingByWeightId
VWDictionary_vwd
float _wordsMaxDepth
std::map< int, double > _workingMem

Detailed Description

Definition at line 56 of file Memory.h.


Constructor & Destructor Documentation

Definition at line 59 of file Memory.cpp.

rtabmap::Memory::~Memory ( ) [virtual]

Definition at line 327 of file Memory.cpp.


Member Function Documentation

Signature * rtabmap::Memory::_getSignature ( int  id) const [private]

Definition at line 765 of file Memory.cpp.

bool rtabmap::Memory::addLink ( int  to,
int  from,
const Transform transform,
Link::Type  type,
float  rotVariance,
float  transVariance 
)

Definition at line 2629 of file Memory.cpp.

void rtabmap::Memory::addSignatureToStm ( Signature signature,
float  poseRotVariance,
float  poseTransVariance 
) [private]

Definition at line 676 of file Memory.cpp.

void rtabmap::Memory::addSignatureToWm ( Signature signature) [private]

Definition at line 745 of file Memory.cpp.

Definition at line 4090 of file Memory.cpp.

std::list< int > rtabmap::Memory::cleanup ( const std::list< int > &  ignoredIds = std::list<int>())

Definition at line 1384 of file Memory.cpp.

void rtabmap::Memory::clear ( ) [private]

Definition at line 1088 of file Memory.cpp.

Transform rtabmap::Memory::computeIcpTransform ( int  oldId,
int  newId,
Transform  guess,
bool  icp3D,
std::string *  rejectedMsg = 0,
int *  correspondences = 0,
double *  variance = 0,
float *  correspondencesRatio = 0 
)

Definition at line 2098 of file Memory.cpp.

Transform rtabmap::Memory::computeIcpTransform ( const Signature oldS,
const Signature newS,
Transform  guess,
bool  icp3D,
std::string *  rejectedMsg = 0,
int *  correspondences = 0,
double *  variance = 0,
float *  correspondencesRatio = 0 
) const

Definition at line 2179 of file Memory.cpp.

std::map< int, float > rtabmap::Memory::computeLikelihood ( const Signature signature,
const std::list< int > &  ids 
)

Compute the likelihood of the signature with some others in the memory. Important: Assuming that all other ids are under 'signature' id. If an error occurs, the result is empty.

Definition at line 1190 of file Memory.cpp.

Transform rtabmap::Memory::computeScanMatchingTransform ( int  newId,
int  oldId,
const std::map< int, Transform > &  poses,
std::string *  rejectedMsg = 0,
int *  inliers = 0,
double *  variance = 0 
)

Definition at line 2484 of file Memory.cpp.

Transform rtabmap::Memory::computeVisualTransform ( int  oldId,
int  newId,
std::string *  rejectedMsg = 0,
int *  inliers = 0,
double *  variance = 0 
) const

Definition at line 1887 of file Memory.cpp.

Transform rtabmap::Memory::computeVisualTransform ( const Signature oldS,
const Signature newS,
std::string *  rejectedMsg = 0,
int *  inliers = 0,
double *  variance = 0 
) const

Definition at line 1916 of file Memory.cpp.

void rtabmap::Memory::copyData ( const Signature from,
Signature to 
) [private]

Definition at line 3455 of file Memory.cpp.

void rtabmap::Memory::createGraph ( GraphNode parent,
unsigned int  maxDepth,
const std::set< int > &  endIds = std::set<int>() 
)

Definition at line 3419 of file Memory.cpp.

Signature * rtabmap::Memory::createSignature ( const SensorData data,
Statistics stats = 0 
) [private]

Definition at line 3519 of file Memory.cpp.

void rtabmap::Memory::deleteLocation ( int  locationId,
std::list< int > *  deletedWords = 0 
)

Definition at line 1816 of file Memory.cpp.

void rtabmap::Memory::disableWordsRef ( int  signatureId) [private]

Definition at line 4068 of file Memory.cpp.

void rtabmap::Memory::dumpDictionary ( const char *  fileNameRef,
const char *  fileNameDesc 
) const

Definition at line 2741 of file Memory.cpp.

void rtabmap::Memory::dumpMemory ( std::string  directory) const [virtual]

Definition at line 2732 of file Memory.cpp.

void rtabmap::Memory::dumpMemoryTree ( const char *  fileNameTree) const

Definition at line 2804 of file Memory.cpp.

void rtabmap::Memory::dumpSignatures ( const char *  fileNameSign,
bool  words3D 
) const [virtual]

Definition at line 2749 of file Memory.cpp.

Definition at line 1403 of file Memory.cpp.

void rtabmap::Memory::enableWordsRef ( const std::list< int > &  signatureIds) [private]

Definition at line 4116 of file Memory.cpp.

std::list< int > rtabmap::Memory::forget ( const std::set< int > &  ignoredIds = std::set<int>())

Definition at line 1328 of file Memory.cpp.

void rtabmap::Memory::generateGraph ( const std::string &  fileName,
std::set< int >  ids = std::set<int>() 
)

Definition at line 3200 of file Memory.cpp.

std::map< int, std::string > rtabmap::Memory::getAllLabels ( ) const

Definition at line 1771 of file Memory.cpp.

std::set< int > rtabmap::Memory::getAllSignatureIds ( ) const

Definition at line 1074 of file Memory.cpp.

bool rtabmap::Memory::getBowForce2D ( ) const [inline]

Definition at line 171 of file Memory.h.

float rtabmap::Memory::getBowInlierDistance ( ) const [inline]

Definition at line 167 of file Memory.h.

int rtabmap::Memory::getBowIterations ( ) const [inline]

Definition at line 168 of file Memory.h.

float rtabmap::Memory::getBowMaxDepth ( ) const [inline]

Definition at line 170 of file Memory.h.

int rtabmap::Memory::getBowMinInliers ( ) const [inline]

Definition at line 169 of file Memory.h.

Definition at line 1059 of file Memory.cpp.

Definition at line 1069 of file Memory.cpp.

const Feature2D* rtabmap::Memory::getFeature2D ( ) const [inline]

Definition at line 143 of file Memory.h.

Definition at line 159 of file Memory.h.

cv::Mat rtabmap::Memory::getImageCompressed ( int  signatureId) const

Definition at line 3067 of file Memory.cpp.

Definition at line 142 of file Memory.h.

Definition at line 1700 of file Memory.cpp.

Definition at line 1705 of file Memory.cpp.

std::map< int, Link > rtabmap::Memory::getLoopClosureLinks ( int  signatureId,
bool  lookInDatabase = false 
) const

Definition at line 805 of file Memory.cpp.

int rtabmap::Memory::getMaxStMemSize ( ) const [inline]

Definition at line 105 of file Memory.h.

void rtabmap::Memory::getMetricConstraints ( const std::set< int > &  ids,
std::map< int, Transform > &  poses,
std::multimap< int, Link > &  links,
bool  lookInDatabase = false 
)

Definition at line 4264 of file Memory.cpp.

std::map< int, Link > rtabmap::Memory::getNeighborLinks ( int  signatureId,
bool  lookInDatabase = false 
) const

Definition at line 775 of file Memory.cpp.

std::map< int, int > rtabmap::Memory::getNeighborsId ( int  signatureId,
int  maxGraphDepth,
int  maxCheckedInDatabase = -1,
bool  incrementMarginOnLoop = false,
bool  ignoreLoopIds = false,
double *  dbAccessTime = 0 
) const

Definition at line 844 of file Memory.cpp.

std::map< int, float > rtabmap::Memory::getNeighborsIdRadius ( int  signatureId,
float  radius,
const std::map< int, Transform > &  optimizedPoses,
int  maxGraphDepth 
) const

Definition at line 937 of file Memory.cpp.

int rtabmap::Memory::getNextId ( ) [private]

Definition at line 1003 of file Memory.cpp.

int rtabmap::Memory::getNi ( int  signatureId) const [private]

Definition at line 3439 of file Memory.cpp.

bool rtabmap::Memory::getNodeInfo ( int  signatureId,
Transform odomPose,
int &  mapId,
int &  weight,
std::string &  label,
double &  stamp,
std::vector< unsigned char > &  userData,
bool  lookInDatabase = false 
) const

Definition at line 3040 of file Memory.cpp.

Transform rtabmap::Memory::getOdomPose ( int  signatureId,
bool  lookInDatabase = false 
) const

Definition at line 3029 of file Memory.cpp.

std::list< Signature * > rtabmap::Memory::getRemovableSignatures ( int  count,
const std::set< int > &  ignoredIds = std::set<int>() 
) [private]

Definition at line 1452 of file Memory.cpp.

const Signature * rtabmap::Memory::getSignature ( int  id) const

Definition at line 760 of file Memory.cpp.

Signature rtabmap::Memory::getSignatureData ( int  locationId,
bool  uncompressedData = false 
)

Definition at line 3082 of file Memory.cpp.

Definition at line 3150 of file Memory.cpp.

int rtabmap::Memory::getSignatureIdByLabel ( const std::string &  label,
bool  lookInDatabase = true 
) const

Definition at line 1711 of file Memory.cpp.

const std::map<int, Signature*>& rtabmap::Memory::getSignatures ( ) const [inline, private]

Definition at line 199 of file Memory.h.

float rtabmap::Memory::getSimilarityThreshold ( ) const [inline]

Definition at line 112 of file Memory.h.

const std::set<int>& rtabmap::Memory::getStMem ( ) const [inline]

Definition at line 104 of file Memory.h.

Definition at line 770 of file Memory.cpp.

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

Definition at line 1306 of file Memory.cpp.

const std::map<int, double>& rtabmap::Memory::getWorkingMem ( ) const [inline]

Definition at line 103 of file Memory.h.

Definition at line 1008 of file Memory.cpp.

bool rtabmap::Memory::init ( const std::string &  dbUrl,
bool  dbOverwritten = false,
const ParametersMap parameters = ParametersMap(),
bool  postInitClosingEvents = false 
)

Definition at line 135 of file Memory.cpp.

void rtabmap::Memory::initCountId ( ) [private]
bool rtabmap::Memory::isBinDataKept ( ) const [inline]

Definition at line 111 of file Memory.h.

bool rtabmap::Memory::isIDsGenerated ( ) const [inline]

Definition at line 141 of file Memory.h.

bool rtabmap::Memory::isIncremental ( ) const [inline]

Definition at line 136 of file Memory.h.

bool rtabmap::Memory::isInLTM ( int  signatureId) const [inline]

Definition at line 140 of file Memory.h.

bool rtabmap::Memory::isInSTM ( int  signatureId) const [inline]

Definition at line 138 of file Memory.h.

bool rtabmap::Memory::isInWM ( int  signatureId) const [inline]

Definition at line 139 of file Memory.h.

bool rtabmap::Memory::isRawDataKept ( ) const [inline]

Definition at line 110 of file Memory.h.

Definition at line 1411 of file Memory.cpp.

bool rtabmap::Memory::labelSignature ( int  id,
const std::string &  label 
)

Definition at line 1734 of file Memory.cpp.

bool rtabmap::Memory::memoryChanged ( ) const [inline]

Definition at line 135 of file Memory.h.

void rtabmap::Memory::moveToTrash ( Signature s,
bool  keepLinkedToGraph = true,
std::list< int > *  deletedWords = 0 
) [private]

If saveToDatabase=false, deleted words are filled in deletedWords.

Definition at line 1586 of file Memory.cpp.

void rtabmap::Memory::parseParameters ( const ParametersMap parameters) [virtual]

Definition at line 386 of file Memory.cpp.

void rtabmap::Memory::preUpdate ( ) [private]

Definition at line 524 of file Memory.cpp.

std::set< int > rtabmap::Memory::reactivateSignatures ( const std::list< int > &  ids,
unsigned int  maxLoaded,
double &  timeDbAccess 
)

Definition at line 4220 of file Memory.cpp.

void rtabmap::Memory::rehearsal ( Signature signature,
Statistics stats = 0 
) [private]

Definition at line 2860 of file Memory.cpp.

bool rtabmap::Memory::rehearsalMerge ( int  oldId,
int  newId 
) [private]

Definition at line 2937 of file Memory.cpp.

Definition at line 2723 of file Memory.cpp.

void rtabmap::Memory::removeLink ( int  idA,
int  idB 
)

Definition at line 1826 of file Memory.cpp.

void rtabmap::Memory::setRoi ( const std::string &  roi)

Definition at line 645 of file Memory.cpp.

bool rtabmap::Memory::setUserData ( int  id,
const std::vector< unsigned char > &  data 
)

Definition at line 1788 of file Memory.cpp.

bool rtabmap::Memory::update ( const SensorData data,
Statistics stats = 0 
)

Definition at line 535 of file Memory.cpp.

void rtabmap::Memory::updateAge ( int  signatureId)

Definition at line 1050 of file Memory.cpp.

void rtabmap::Memory::updateLink ( int  fromId,
int  toId,
const Transform transform,
float  rotVariance,
float  transVariance 
)

Definition at line 2698 of file Memory.cpp.


Member Data Documentation

Definition at line 227 of file Memory.h.

Definition at line 252 of file Memory.h.

Definition at line 219 of file Memory.h.

Definition at line 264 of file Memory.h.

Definition at line 265 of file Memory.h.

Definition at line 263 of file Memory.h.

Definition at line 260 of file Memory.h.

Definition at line 261 of file Memory.h.

Definition at line 262 of file Memory.h.

Definition at line 259 of file Memory.h.

Definition at line 213 of file Memory.h.

Definition at line 250 of file Memory.h.

Definition at line 251 of file Memory.h.

Definition at line 226 of file Memory.h.

Definition at line 279 of file Memory.h.

Definition at line 277 of file Memory.h.

Definition at line 278 of file Memory.h.

Definition at line 280 of file Memory.h.

Definition at line 274 of file Memory.h.

Definition at line 268 of file Memory.h.

Definition at line 272 of file Memory.h.

Definition at line 269 of file Memory.h.

Definition at line 273 of file Memory.h.

Definition at line 267 of file Memory.h.

Definition at line 266 of file Memory.h.

Definition at line 275 of file Memory.h.

Definition at line 276 of file Memory.h.

Definition at line 271 of file Memory.h.

Definition at line 270 of file Memory.h.

Definition at line 235 of file Memory.h.

Definition at line 236 of file Memory.h.

Definition at line 225 of file Memory.h.

Definition at line 228 of file Memory.h.

Definition at line 221 of file Memory.h.

Definition at line 229 of file Memory.h.

Definition at line 238 of file Memory.h.

Definition at line 237 of file Memory.h.

Definition at line 240 of file Memory.h.

Definition at line 230 of file Memory.h.

Definition at line 222 of file Memory.h.

Definition at line 239 of file Memory.h.

Definition at line 220 of file Memory.h.

Definition at line 254 of file Memory.h.

Definition at line 242 of file Memory.h.

Definition at line 218 of file Memory.h.

Definition at line 223 of file Memory.h.

Definition at line 232 of file Memory.h.

Definition at line 231 of file Memory.h.

Definition at line 233 of file Memory.h.

std::vector<float> rtabmap::Memory::_roiRatios [private]

Definition at line 256 of file Memory.h.

std::map<int, Signature *> rtabmap::Memory::_signatures [private]

Definition at line 244 of file Memory.h.

Definition at line 241 of file Memory.h.

Definition at line 217 of file Memory.h.

Definition at line 285 of file Memory.h.

Definition at line 284 of file Memory.h.

Definition at line 286 of file Memory.h.

Definition at line 283 of file Memory.h.

Definition at line 287 of file Memory.h.

std::set<int> rtabmap::Memory::_stMem [private]

Definition at line 245 of file Memory.h.

double rtabmap::Memory::_subPixEps [private]

Definition at line 291 of file Memory.h.

Definition at line 290 of file Memory.h.

Definition at line 289 of file Memory.h.

Definition at line 252 of file Memory.h.

Definition at line 224 of file Memory.h.

Definition at line 249 of file Memory.h.

Definition at line 255 of file Memory.h.

std::map<int, double> rtabmap::Memory::_workingMem [private]

Definition at line 246 of file Memory.h.

const int rtabmap::Memory::kIdInvalid = 0 [static]

Definition at line 61 of file Memory.h.

const int rtabmap::Memory::kIdStart = 0 [static]

Definition at line 59 of file Memory.h.

const int rtabmap::Memory::kIdVirtual = -1 [static]

Definition at line 60 of file Memory.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:44