#include <Memory.h>
Public Member Functions | |
bool | addLink (const Link &link, bool addInDatabase=false) |
int | cleanup () |
void | close (bool databaseSaved=true, bool postInitClosingEvents=false, const std::string &ouputDatabasePath="") |
Transform | computeIcpTransformMulti (int newId, int oldId, const std::map< int, Transform > &poses, RegistrationInfo *info=0) |
std::map< int, float > | computeLikelihood (const Signature *signature, const std::list< int > &ids) |
Transform | computeTransform (Signature &fromS, Signature &toS, Transform guess, RegistrationInfo *info=0, bool useKnownCorrespondencesIfPossible=false) const |
Transform | computeTransform (int fromId, int toId, Transform guess, RegistrationInfo *info=0, bool useKnownCorrespondencesIfPossible=false) |
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, const std::set< int > &ids=std::set< int >()) |
std::map< int, std::string > | getAllLabels () const |
std::multimap< int, Link > | getAllLinks (bool lookInDatabase, bool ignoreNullLinks=true) const |
std::set< int > | getAllSignatureIds () const |
int | getDatabaseMemoryUsed () const |
std::string | getDatabaseUrl () const |
std::string | getDatabaseVersion () const |
double | getDbSavingTime () const |
const Feature2D * | getFeature2D () const |
Transform | getGroundTruthPose (int signatureId, bool lookInDatabase=false) const |
cv::Mat | getImageCompressed (int signatureId) const |
int | getLastGlobalLoopClosureId () const |
int | getLastSignatureId () const |
const Signature * | getLastWorkingSignature () const |
std::map< int, Link > | getLinks (int signatureId, bool lookInDatabase=false) const |
std::map< int, Link > | getLoopClosureLinks (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, Link > | getNeighborLinks (int signatureId, bool lookInDatabase=false) const |
std::map< int, int > | getNeighborsId (int signatureId, int maxGraphDepth, int maxCheckedInDatabase=-1, bool incrementMarginOnLoop=false, bool ignoreLoopIds=false, bool ignoreIntermediateNodes=false, bool ignoreLocalSpaceLoopIds=false, const std::set< int > &nodesSet=std::set< int >(), double *dbAccessTime=0) const |
std::map< int, float > | getNeighborsIdRadius (int signatureId, float radius, const std::map< int, Transform > &optimizedPoses, int maxGraphDepth) const |
void | getNodeCalibration (int nodeId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) |
SensorData | getNodeData (int nodeId, bool uncompressedData=false) const |
bool | getNodeInfo (int signatureId, Transform &odomPose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruth, std::vector< float > &velocity, GPS &gps, bool lookInDatabase=false) const |
void | getNodeWords (int nodeId, std::multimap< int, cv::KeyPoint > &words, std::multimap< int, cv::Point3f > &words3, std::multimap< int, cv::Mat > &wordsDescriptors) |
Transform | getOdomPose (int signatureId, bool lookInDatabase=false) const |
virtual const ParametersMap & | getParameters () const |
const Signature * | getSignature (int id) const |
SensorData | getSignatureDataConst (int locationId, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const |
int | getSignatureIdByLabel (const std::string &label, bool lookInDatabase=true) const |
float | getSimilarityThreshold () const |
const std::set< int > & | getStMem () const |
const VWDictionary * | getVWDictionary () const |
std::map< int, int > | getWeights () const |
const std::map< int, double > & | getWorkingMem () const |
int | incrementMapId (std::map< int, int > *reducedIds=0) |
bool | init (const std::string &dbUrl, bool dbOverwritten=false, const ParametersMap ¶meters=ParametersMap(), bool postInitClosingEvents=false) |
bool | isBinDataKept () const |
bool | isGraphReduced () const |
bool | isIDsGenerated () const |
bool | isIncremental () const |
bool | isInLTM (int signatureId) const |
bool | isInSTM (int signatureId) const |
bool | isInWM (int signatureId) const |
void | joinTrashThread () |
bool | labelSignature (int id, const std::string &label) |
cv::Mat | load2DMap (float &xMin, float &yMin, float &cellSize) const |
cv::Mat | loadOptimizedMesh (std::vector< std::vector< std::vector< unsigned int > > > *polygons=0, std::vector< std::vector< Eigen::Vector2f > > *texCoords=0, cv::Mat *textures=0) const |
std::map< int, Transform > | loadOptimizedPoses (Transform *lastlocalizationPose) const |
cv::Mat | loadPreviewImage () const |
Memory (const ParametersMap ¶meters=ParametersMap()) | |
bool | memoryChanged () const |
virtual void | parseParameters (const ParametersMap ¶meters) |
std::set< int > | reactivateSignatures (const std::list< int > &ids, unsigned int maxLoaded, double &timeDbAccess) |
void | removeAllVirtualLinks () |
void | removeLink (int idA, int idB) |
void | removeRawData (int id, bool image=true, bool scan=true, bool userData=true) |
void | removeVirtualLinks (int signatureId) |
void | save2DMap (const cv::Mat &map, float xMin, float yMin, float cellSize) const |
void | saveLocationData (int locationId) |
void | saveOptimizedMesh (const cv::Mat &cloud, const std::vector< std::vector< std::vector< unsigned int > > > &polygons=std::vector< std::vector< std::vector< unsigned int > > >(), const std::vector< std::vector< Eigen::Vector2f > > &texCoords=std::vector< std::vector< Eigen::Vector2f > >(), const cv::Mat &textures=cv::Mat()) const |
void | saveOptimizedPoses (const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const |
void | savePreviewImage (const cv::Mat &image) const |
void | saveStatistics (const Statistics &statistics) |
bool | setUserData (int id, const cv::Mat &data) |
bool | update (const SensorData &data, Statistics *stats=0) |
bool | update (const SensorData &data, const Transform &pose, const cv::Mat &covariance, const std::vector< float > &velocity=std::vector< float >(), Statistics *stats=0) |
void | updateAge (int signatureId) |
void | updateLink (const Link &link, bool updateInDatabase=false) |
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, const cv::Mat &covariance) |
void | addSignatureToWmFromLTM (Signature *signature) |
void | cleanUnusedWords () |
void | clear () |
void | copyData (const Signature *from, Signature *to) |
Signature * | createSignature (const SensorData &data, const Transform &pose, 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 | loadDataFromDb (bool postInitClosingEvents) |
void | moveSignatureToWMFromSTM (int id, int *reducedTo=0) |
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 | _compressionParallelized |
bool | _covOffDiagonalIgnored |
bool | _createOccupancyGrid |
bool | _depthAsMask |
Feature2D * | _feature2D |
bool | _generateIds |
GPS | _gpsOrigin |
int | _idCount |
int | _idMapCount |
bool | _idUpdatedToNewOneRehearsal |
int | _imagePostDecimation |
int | _imagePreDecimation |
bool | _imagesAlreadyRectified |
bool | _incrementalMemory |
float | _laserScanDownsampleStepSize |
int | _laserScanNormalK |
float | _laserScanNormalRadius |
float | _laserScanVoxelSize |
int | _lastGlobalLoopClosureId |
Signature * | _lastSignature |
bool | _linksChanged |
bool | _localBundleOnLoopClosure |
bool | _mapLabelsAdded |
int | _maxStMemSize |
bool | _memoryChanged |
bool | _notLinkedNodesKeptInDb |
OccupancyGrid * | _occupancy |
bool | _parallelized |
bool | _rawDescriptorsKept |
float | _recentWmRatio |
std::vector< CameraModel > | _rectCameraModels |
bool | _rectifyOnlyFeatures |
StereoCameraModel | _rectStereoCameraModel |
bool | _reduceGraph |
bool | _reextractLoopClosureFeatures |
RegistrationIcp * | _registrationIcpMulti |
Registration * | _registrationPipeline |
float | _rehearsalMaxAngle |
float | _rehearsalMaxDistance |
bool | _rehearsalWeightIgnoredWhileMoving |
bool | _saveDepth16Format |
bool | _saveIntermediateNodeData |
std::map< int, Signature * > | _signatures |
int | _signaturesAdded |
float | _similarityThreshold |
std::set< int > | _stMem |
bool | _tfIdfLikelihoodUsed |
bool | _transferSortingByWeightId |
bool | _useOdometryFeatures |
int | _visCorType |
int | _visMaxFeatures |
VWDictionary * | _vwd |
std::map< int, double > | _workingMem |
ParametersMap | parameters_ |
rtabmap::Memory::Memory | ( | const ParametersMap & | parameters = ParametersMap() | ) |
Definition at line 72 of file Memory.cpp.
rtabmap::Memory::~Memory | ( | ) | [virtual] |
Definition at line 427 of file Memory.cpp.
Signature * rtabmap::Memory::_getSignature | ( | int | id | ) | const [private] |
Definition at line 1013 of file Memory.cpp.
bool rtabmap::Memory::addLink | ( | const Link & | link, |
bool | addInDatabase = false |
||
) |
Definition at line 2856 of file Memory.cpp.
void rtabmap::Memory::addSignatureToStm | ( | Signature * | signature, |
const cv::Mat & | covariance | ||
) | [private] |
Definition at line 787 of file Memory.cpp.
void rtabmap::Memory::addSignatureToWmFromLTM | ( | Signature * | signature | ) | [private] |
Definition at line 892 of file Memory.cpp.
void rtabmap::Memory::cleanUnusedWords | ( | ) | [private] |
Definition at line 4642 of file Memory.cpp.
int rtabmap::Memory::cleanup | ( | ) |
Definition at line 1757 of file Memory.cpp.
void rtabmap::Memory::clear | ( | ) | [private] |
Definition at line 1424 of file Memory.cpp.
void rtabmap::Memory::close | ( | bool | databaseSaved = true , |
bool | postInitClosingEvents = false , |
||
const std::string & | ouputDatabasePath = "" |
||
) |
Definition at line 370 of file Memory.cpp.
Transform rtabmap::Memory::computeIcpTransformMulti | ( | int | newId, |
int | oldId, | ||
const std::map< int, Transform > & | poses, | ||
RegistrationInfo * | info = 0 |
||
) |
Definition at line 2698 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 1545 of file Memory.cpp.
Transform rtabmap::Memory::computeTransform | ( | Signature & | fromS, |
Signature & | toS, | ||
Transform | guess, | ||
RegistrationInfo * | info = 0 , |
||
bool | useKnownCorrespondencesIfPossible = false |
||
) | const |
Definition at line 2412 of file Memory.cpp.
Transform rtabmap::Memory::computeTransform | ( | int | fromId, |
int | toId, | ||
Transform | guess, | ||
RegistrationInfo * | info = 0 , |
||
bool | useKnownCorrespondencesIfPossible = false |
||
) |
Definition at line 2383 of file Memory.cpp.
void rtabmap::Memory::copyData | ( | const Signature * | from, |
Signature * | to | ||
) | [private] |
Definition at line 3579 of file Memory.cpp.
Signature * rtabmap::Memory::createSignature | ( | const SensorData & | data, |
const Transform & | pose, | ||
Statistics * | stats = 0 |
||
) | [private] |
Definition at line 3630 of file Memory.cpp.
void rtabmap::Memory::deleteLocation | ( | int | locationId, |
std::list< int > * | deletedWords = 0 |
||
) |
Definition at line 2266 of file Memory.cpp.
void rtabmap::Memory::disableWordsRef | ( | int | signatureId | ) | [private] |
Definition at line 4620 of file Memory.cpp.
void rtabmap::Memory::dumpDictionary | ( | const char * | fileNameRef, |
const char * | fileNameDesc | ||
) | const |
Definition at line 3049 of file Memory.cpp.
void rtabmap::Memory::dumpMemory | ( | std::string | directory | ) | const [virtual] |
Definition at line 3040 of file Memory.cpp.
void rtabmap::Memory::dumpMemoryTree | ( | const char * | fileNameTree | ) | const |
Definition at line 3105 of file Memory.cpp.
void rtabmap::Memory::dumpSignatures | ( | const char * | fileNameSign, |
bool | words3D | ||
) | const [virtual] |
Definition at line 3057 of file Memory.cpp.
void rtabmap::Memory::emptyTrash | ( | ) |
Definition at line 1866 of file Memory.cpp.
void rtabmap::Memory::enableWordsRef | ( | const std::list< int > & | signatureIds | ) | [private] |
Definition at line 4665 of file Memory.cpp.
std::list< int > rtabmap::Memory::forget | ( | const std::set< int > & | ignoredIds = std::set<int>() | ) |
Definition at line 1685 of file Memory.cpp.
void rtabmap::Memory::generateGraph | ( | const std::string & | fileName, |
const std::set< int > & | ids = std::set<int>() |
||
) |
Definition at line 3552 of file Memory.cpp.
std::map< int, std::string > rtabmap::Memory::getAllLabels | ( | ) | const |
Definition at line 2234 of file Memory.cpp.
std::multimap< int, Link > rtabmap::Memory::getAllLinks | ( | bool | lookInDatabase, |
bool | ignoreNullLinks = true |
||
) | const |
Definition at line 1126 of file Memory.cpp.
std::set< int > rtabmap::Memory::getAllSignatureIds | ( | ) | const |
Definition at line 1410 of file Memory.cpp.
int rtabmap::Memory::getDatabaseMemoryUsed | ( | ) | const |
Definition at line 1374 of file Memory.cpp.
std::string rtabmap::Memory::getDatabaseUrl | ( | ) | const |
Definition at line 1395 of file Memory.cpp.
std::string rtabmap::Memory::getDatabaseVersion | ( | ) | const |
Definition at line 1385 of file Memory.cpp.
double rtabmap::Memory::getDbSavingTime | ( | ) | const |
Definition at line 1405 of file Memory.cpp.
const Feature2D* rtabmap::Memory::getFeature2D | ( | ) | const [inline] |
Transform rtabmap::Memory::getGroundTruthPose | ( | int | signatureId, |
bool | lookInDatabase = false |
||
) | const |
Definition at line 3390 of file Memory.cpp.
cv::Mat rtabmap::Memory::getImageCompressed | ( | int | signatureId | ) | const |
Definition at line 3433 of file Memory.cpp.
int rtabmap::Memory::getLastGlobalLoopClosureId | ( | ) | const [inline] |
int rtabmap::Memory::getLastSignatureId | ( | ) | const |
Definition at line 2160 of file Memory.cpp.
const Signature * rtabmap::Memory::getLastWorkingSignature | ( | ) | const |
Definition at line 2165 of file Memory.cpp.
std::map< int, Link > rtabmap::Memory::getLinks | ( | int | signatureId, |
bool | lookInDatabase = false |
||
) | const |
Definition at line 1105 of file Memory.cpp.
std::map< int, Link > rtabmap::Memory::getLoopClosureLinks | ( | int | signatureId, |
bool | lookInDatabase = false |
||
) | const |
Definition at line 1065 of file Memory.cpp.
int rtabmap::Memory::getMaxStMemSize | ( | ) | const [inline] |
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 4821 of file Memory.cpp.
std::map< int, Link > rtabmap::Memory::getNeighborLinks | ( | int | signatureId, |
bool | lookInDatabase = false |
||
) | const |
Definition at line 1023 of file Memory.cpp.
std::map< int, int > rtabmap::Memory::getNeighborsId | ( | int | signatureId, |
int | maxGraphDepth, | ||
int | maxCheckedInDatabase = -1 , |
||
bool | incrementMarginOnLoop = false , |
||
bool | ignoreLoopIds = false , |
||
bool | ignoreIntermediateNodes = false , |
||
bool | ignoreLocalSpaceLoopIds = false , |
||
const std::set< int > & | nodesSet = std::set<int>() , |
||
double * | dbAccessTime = 0 |
||
) | const |
Definition at line 1156 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 1273 of file Memory.cpp.
int rtabmap::Memory::getNextId | ( | ) | [private] |
Definition at line 1337 of file Memory.cpp.
int rtabmap::Memory::getNi | ( | int | signatureId | ) | const [private] |
Definition at line 3563 of file Memory.cpp.
void rtabmap::Memory::getNodeCalibration | ( | int | nodeId, |
std::vector< CameraModel > & | models, | ||
StereoCameraModel & | stereoModel | ||
) |
Definition at line 3512 of file Memory.cpp.
SensorData rtabmap::Memory::getNodeData | ( | int | nodeId, |
bool | uncompressedData = false |
||
) | const |
Definition at line 3450 of file Memory.cpp.
bool rtabmap::Memory::getNodeInfo | ( | int | signatureId, |
Transform & | odomPose, | ||
int & | mapId, | ||
int & | weight, | ||
std::string & | label, | ||
double & | stamp, | ||
Transform & | groundTruth, | ||
std::vector< float > & | velocity, | ||
GPS & | gps, | ||
bool | lookInDatabase = false |
||
) | const |
Definition at line 3402 of file Memory.cpp.
void rtabmap::Memory::getNodeWords | ( | int | nodeId, |
std::multimap< int, cv::KeyPoint > & | words, | ||
std::multimap< int, cv::Point3f > & | words3, | ||
std::multimap< int, cv::Mat > & | wordsDescriptors | ||
) |
Definition at line 3473 of file Memory.cpp.
Transform rtabmap::Memory::getOdomPose | ( | int | signatureId, |
bool | lookInDatabase = false |
||
) | const |
Definition at line 3378 of file Memory.cpp.
virtual const ParametersMap& rtabmap::Memory::getParameters | ( | ) | const [inline, virtual] |
std::list< Signature * > rtabmap::Memory::getRemovableSignatures | ( | int | count, |
const std::set< int > & | ignoredIds = std::set<int>() |
||
) | [private] |
Definition at line 1915 of file Memory.cpp.
const Signature * rtabmap::Memory::getSignature | ( | int | id | ) | const |
Definition at line 1008 of file Memory.cpp.
SensorData rtabmap::Memory::getSignatureDataConst | ( | int | locationId, |
bool | images = true , |
||
bool | scan = true , |
||
bool | userData = true , |
||
bool | occupancyGrid = true |
||
) | const |
Definition at line 3530 of file Memory.cpp.
int rtabmap::Memory::getSignatureIdByLabel | ( | const std::string & | label, |
bool | lookInDatabase = true |
||
) | const |
Definition at line 2171 of file Memory.cpp.
const std::map<int, Signature*>& rtabmap::Memory::getSignatures | ( | ) | const [inline, private] |
float rtabmap::Memory::getSimilarityThreshold | ( | ) | const [inline] |
const std::set<int>& rtabmap::Memory::getStMem | ( | ) | const [inline] |
const VWDictionary * rtabmap::Memory::getVWDictionary | ( | ) | const |
Definition at line 1018 of file Memory.cpp.
std::map< int, int > rtabmap::Memory::getWeights | ( | ) | const |
Definition at line 1663 of file Memory.cpp.
const std::map<int, double>& rtabmap::Memory::getWorkingMem | ( | ) | const [inline] |
int rtabmap::Memory::incrementMapId | ( | std::map< int, int > * | reducedIds = 0 | ) |
Definition at line 1342 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 142 of file Memory.cpp.
void rtabmap::Memory::initCountId | ( | ) | [private] |
bool rtabmap::Memory::isBinDataKept | ( | ) | const [inline] |
bool rtabmap::Memory::isGraphReduced | ( | ) | const [inline] |
bool rtabmap::Memory::isIDsGenerated | ( | ) | const [inline] |
bool rtabmap::Memory::isIncremental | ( | ) | const [inline] |
bool rtabmap::Memory::isInLTM | ( | int | signatureId | ) | const [inline] |
bool rtabmap::Memory::isInSTM | ( | int | signatureId | ) | const [inline] |
bool rtabmap::Memory::isInWM | ( | int | signatureId | ) | const [inline] |
void rtabmap::Memory::joinTrashThread | ( | ) |
Definition at line 1874 of file Memory.cpp.
bool rtabmap::Memory::labelSignature | ( | int | id, |
const std::string & | label | ||
) |
Definition at line 2194 of file Memory.cpp.
cv::Mat rtabmap::Memory::load2DMap | ( | float & | xMin, |
float & | yMin, | ||
float & | cellSize | ||
) | const |
Definition at line 1825 of file Memory.cpp.
void rtabmap::Memory::loadDataFromDb | ( | bool | postInitClosingEvents | ) | [private] |
Definition at line 207 of file Memory.cpp.
cv::Mat rtabmap::Memory::loadOptimizedMesh | ( | std::vector< std::vector< std::vector< unsigned int > > > * | polygons = 0 , |
std::vector< std::vector< Eigen::Vector2f > > * | texCoords = 0 , |
||
cv::Mat * | textures = 0 |
||
) | const |
Definition at line 1850 of file Memory.cpp.
std::map< int, Transform > rtabmap::Memory::loadOptimizedPoses | ( | Transform * | lastlocalizationPose | ) | const |
Definition at line 1808 of file Memory.cpp.
cv::Mat rtabmap::Memory::loadPreviewImage | ( | ) | const |
Definition at line 1791 of file Memory.cpp.
bool rtabmap::Memory::memoryChanged | ( | ) | const [inline] |
void rtabmap::Memory::moveSignatureToWMFromSTM | ( | int | id, |
int * | reducedTo = 0 |
||
) | [private] |
Definition at line 907 of file Memory.cpp.
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 2046 of file Memory.cpp.
void rtabmap::Memory::parseParameters | ( | const ParametersMap & | parameters | ) | [virtual] |
Definition at line 442 of file Memory.cpp.
void rtabmap::Memory::preUpdate | ( | ) | [private] |
Definition at line 649 of file Memory.cpp.
std::set< int > rtabmap::Memory::reactivateSignatures | ( | const std::list< int > & | ids, |
unsigned int | maxLoaded, | ||
double & | timeDbAccess | ||
) |
Definition at line 4777 of file Memory.cpp.
void rtabmap::Memory::rehearsal | ( | Signature * | signature, |
Statistics * | stats = 0 |
||
) | [private] |
Definition at line 3163 of file Memory.cpp.
bool rtabmap::Memory::rehearsalMerge | ( | int | oldId, |
int | newId | ||
) | [private] |
Definition at line 3220 of file Memory.cpp.
Definition at line 3001 of file Memory.cpp.
void rtabmap::Memory::removeLink | ( | int | idA, |
int | idB | ||
) |
Definition at line 2295 of file Memory.cpp.
void rtabmap::Memory::removeRawData | ( | int | id, |
bool | image = true , |
||
bool | scan = true , |
||
bool | userData = true |
||
) |
Definition at line 2358 of file Memory.cpp.
void rtabmap::Memory::removeVirtualLinks | ( | int | signatureId | ) |
Definition at line 3010 of file Memory.cpp.
void rtabmap::Memory::save2DMap | ( | const cv::Mat & | map, |
float | xMin, | ||
float | yMin, | ||
float | cellSize | ||
) | const |
Definition at line 1817 of file Memory.cpp.
void rtabmap::Memory::saveLocationData | ( | int | locationId | ) |
Definition at line 2276 of file Memory.cpp.
void rtabmap::Memory::saveOptimizedMesh | ( | const cv::Mat & | cloud, |
const std::vector< std::vector< std::vector< unsigned int > > > & | polygons = std::vector<std::vector<std::vector<unsigned int> > >() , |
||
const std::vector< std::vector< Eigen::Vector2f > > & | texCoords = std::vector<std::vector<Eigen::Vector2f> >() , |
||
const cv::Mat & | textures = cv::Mat() |
||
) | const |
Definition at line 1834 of file Memory.cpp.
void rtabmap::Memory::saveOptimizedPoses | ( | const std::map< int, Transform > & | optimizedPoses, |
const Transform & | lastlocalizationPose | ||
) | const |
Definition at line 1800 of file Memory.cpp.
void rtabmap::Memory::savePreviewImage | ( | const cv::Mat & | image | ) | const |
Definition at line 1784 of file Memory.cpp.
void rtabmap::Memory::saveStatistics | ( | const Statistics & | statistics | ) |
Definition at line 1776 of file Memory.cpp.
bool rtabmap::Memory::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 2251 of file Memory.cpp.
bool rtabmap::Memory::update | ( | const SensorData & | data, |
Statistics * | stats = 0 |
||
) |
Definition at line 663 of file Memory.cpp.
bool rtabmap::Memory::update | ( | const SensorData & | data, |
const Transform & | pose, | ||
const cv::Mat & | covariance, | ||
const std::vector< float > & | velocity = std::vector<float>() , |
||
Statistics * | stats = 0 |
||
) |
Definition at line 670 of file Memory.cpp.
void rtabmap::Memory::updateAge | ( | int | signatureId | ) |
Definition at line 1365 of file Memory.cpp.
void rtabmap::Memory::updateLink | ( | const Link & | link, |
bool | updateInDatabase = false |
||
) |
Definition at line 2941 of file Memory.cpp.
bool rtabmap::Memory::_badSignaturesIgnored [private] |
float rtabmap::Memory::_badSignRatio [private] |
bool rtabmap::Memory::_binDataKept [private] |
bool rtabmap::Memory::_compressionParallelized [private] |
bool rtabmap::Memory::_covOffDiagonalIgnored [private] |
bool rtabmap::Memory::_createOccupancyGrid [private] |
DBDriver* rtabmap::Memory::_dbDriver [protected] |
bool rtabmap::Memory::_depthAsMask [private] |
Feature2D* rtabmap::Memory::_feature2D [private] |
bool rtabmap::Memory::_generateIds [private] |
GPS rtabmap::Memory::_gpsOrigin [private] |
int rtabmap::Memory::_idCount [private] |
int rtabmap::Memory::_idMapCount [private] |
bool rtabmap::Memory::_idUpdatedToNewOneRehearsal [private] |
int rtabmap::Memory::_imagePostDecimation [private] |
int rtabmap::Memory::_imagePreDecimation [private] |
bool rtabmap::Memory::_imagesAlreadyRectified [private] |
bool rtabmap::Memory::_incrementalMemory [private] |
float rtabmap::Memory::_laserScanDownsampleStepSize [private] |
int rtabmap::Memory::_laserScanNormalK [private] |
float rtabmap::Memory::_laserScanNormalRadius [private] |
float rtabmap::Memory::_laserScanVoxelSize [private] |
int rtabmap::Memory::_lastGlobalLoopClosureId [private] |
Signature* rtabmap::Memory::_lastSignature [private] |
bool rtabmap::Memory::_linksChanged [private] |
bool rtabmap::Memory::_localBundleOnLoopClosure [private] |
bool rtabmap::Memory::_mapLabelsAdded [private] |
int rtabmap::Memory::_maxStMemSize [private] |
bool rtabmap::Memory::_memoryChanged [private] |
bool rtabmap::Memory::_notLinkedNodesKeptInDb [private] |
OccupancyGrid* rtabmap::Memory::_occupancy [private] |
bool rtabmap::Memory::_parallelized [private] |
bool rtabmap::Memory::_rawDescriptorsKept [private] |
float rtabmap::Memory::_recentWmRatio [private] |
std::vector<CameraModel> rtabmap::Memory::_rectCameraModels [private] |
bool rtabmap::Memory::_rectifyOnlyFeatures [private] |
bool rtabmap::Memory::_reduceGraph [private] |
bool rtabmap::Memory::_reextractLoopClosureFeatures [private] |
float rtabmap::Memory::_rehearsalMaxAngle [private] |
float rtabmap::Memory::_rehearsalMaxDistance [private] |
bool rtabmap::Memory::_rehearsalWeightIgnoredWhileMoving [private] |
bool rtabmap::Memory::_saveDepth16Format [private] |
bool rtabmap::Memory::_saveIntermediateNodeData [private] |
std::map<int, Signature *> rtabmap::Memory::_signatures [private] |
int rtabmap::Memory::_signaturesAdded [private] |
float rtabmap::Memory::_similarityThreshold [private] |
std::set<int> rtabmap::Memory::_stMem [private] |
bool rtabmap::Memory::_tfIdfLikelihoodUsed [private] |
bool rtabmap::Memory::_transferSortingByWeightId [private] |
bool rtabmap::Memory::_useOdometryFeatures [private] |
int rtabmap::Memory::_visCorType [private] |
int rtabmap::Memory::_visMaxFeatures [private] |
VWDictionary* rtabmap::Memory::_vwd [private] |
std::map<int, double> rtabmap::Memory::_workingMem [private] |
const int rtabmap::Memory::kIdInvalid = 0 [static] |
const int rtabmap::Memory::kIdStart = 0 [static] |
const int rtabmap::Memory::kIdVirtual = -1 [static] |
ParametersMap rtabmap::Memory::parameters_ [private] |