#include <DBDriver.h>
Public Member Functions | |
void | addInfoAfterRun (int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize, const ParametersMap ¶meters) const |
void | addLink (const Link &link) |
void | addStatistics (const Statistics &statistics) const |
void | asyncSave (Signature *s) |
void | asyncSave (VisualWord *vw) |
void | beginTransaction () const |
void | closeConnection (bool save=true, const std::string &outputUrl="") |
void | commit () const |
void | emptyTrashes (bool async=false) |
void | executeNoResult (const std::string &sql) const |
void | generateGraph (const std::string &fileName, const std::set< int > &ids=std::set< int >(), const std::map< int, Signature * > &otherSignatures=std::map< int, Signature * >()) |
void | getAllLabels (std::map< int, std::string > &labels) const |
void | getAllLinks (std::multimap< int, Link > &links, bool ignoreNullLinks=true) const |
void | getAllNodeIds (std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const |
std::map< int, std::pair < std::map< std::string, float > , double > > | getAllStatistics () const |
std::map< int, std::vector< int > > | getAllStatisticsWmStates () const |
bool | getCalibration (int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const |
long | getCalibrationsMemoryUsed () const |
std::string | getDatabaseVersion () const |
long | getDepthImagesMemoryUsed () const |
double | getEmptyTrashesTime () const |
long | getFeaturesMemoryUsed () const |
long | getGridsMemoryUsed () const |
long | getImagesMemoryUsed () const |
void | getInvertedIndexNi (int signatureId, int &ni) const |
bool | getLaserScanInfo (int signatureId, LaserScan &info) const |
long | getLaserScansMemoryUsed () const |
int | getLastDictionarySize () const |
void | getLastNodeId (int &id) const |
int | getLastNodesSize () const |
ParametersMap | getLastParameters () const |
void | getLastWordId (int &id) const |
long | getLinksMemoryUsed () const |
long | getMemoryUsed () const |
void | getNodeData (int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const |
void | getNodeIdByLabel (const std::string &label, int &id) const |
bool | getNodeInfo (int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps) const |
long | getNodesMemoryUsed () const |
std::map< std::string, float > | getStatistics (int nodeId, double &stamp, std::vector< int > *wmState=0) const |
long | getStatisticsMemoryUsed () const |
int | getTotalDictionarySize () const |
int | getTotalNodesSize () const |
const std::string & | getUrl () const |
long | getUserDataMemoryUsed () const |
void | getWeight (int signatureId, int &weight) const |
long | getWordsMemoryUsed () const |
bool | isConnected () const |
virtual bool | isInMemory () const |
void | load (VWDictionary *dictionary, bool lastStateOnly=true) const |
cv::Mat | load2DMap (float &xMin, float &yMin, float &cellSize) const |
void | loadLastNodes (std::list< Signature * > &signatures) const |
void | loadLinks (int signatureId, std::map< int, Link > &links, Link::Type type=Link::kUndef) const |
void | loadNodeData (std::list< Signature * > &signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) 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 |
void | loadSignatures (const std::list< int > &ids, std::list< Signature * > &signatures, std::set< int > *loadedFromTrash=0) |
void | loadWords (const std::set< int > &wordIds, std::list< VisualWord * > &vws) |
bool | openConnection (const std::string &url, bool overwritten=false) |
virtual void | parseParameters (const ParametersMap ¶meters) |
void | removeLink (int from, int to) |
void | save2DMap (const cv::Mat &map, float xMin, float yMin, float cellSize) const |
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 | setTimestampUpdateEnabled (bool enabled) |
void | updateDepthImage (int nodeId, const cv::Mat &image) |
void | updateLink (const Link &link) |
void | updateOccupancyGrid (int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewpoint) |
virtual | ~DBDriver () |
Static Public Member Functions | |
static DBDriver * | create (const ParametersMap ¶meters=ParametersMap()) |
Protected Member Functions | |
virtual void | addLinkQuery (const Link &link) const =0 |
virtual void | addStatisticsQuery (const Statistics &statistics) const =0 |
virtual bool | connectDatabaseQuery (const std::string &url, bool overwritten=false)=0 |
DBDriver (const ParametersMap ¶meters=ParametersMap()) | |
virtual void | disconnectDatabaseQuery (bool save=true, const std::string &outputUrl="")=0 |
virtual void | executeNoResultQuery (const std::string &sql) const =0 |
virtual void | getAllLabelsQuery (std::map< int, std::string > &labels) const =0 |
virtual void | getAllLinksQuery (std::multimap< int, Link > &links, bool ignoreNullLinks) const =0 |
virtual void | getAllNodeIdsQuery (std::set< int > &ids, bool ignoreChildren, bool ignoreBadSignatures) const =0 |
virtual std::map< int, std::pair< std::map < std::string, float >, double > > | getAllStatisticsQuery () const =0 |
virtual std::map< int, std::vector< int > > | getAllStatisticsWmStatesQuery () const =0 |
virtual bool | getCalibrationQuery (int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const =0 |
virtual long | getCalibrationsMemoryUsedQuery () const =0 |
virtual bool | getDatabaseVersionQuery (std::string &version) const =0 |
virtual long | getDepthImagesMemoryUsedQuery () const =0 |
virtual long | getFeaturesMemoryUsedQuery () const =0 |
virtual long | getGridsMemoryUsedQuery () const =0 |
virtual long | getImagesMemoryUsedQuery () const =0 |
virtual void | getInvertedIndexNiQuery (int signatureId, int &ni) const =0 |
virtual bool | getLaserScanInfoQuery (int signatureId, LaserScan &info) const =0 |
virtual long | getLaserScansMemoryUsedQuery () const =0 |
virtual int | getLastDictionarySizeQuery () const =0 |
virtual void | getLastIdQuery (const std::string &tableName, int &id) const =0 |
virtual int | getLastNodesSizeQuery () const =0 |
virtual ParametersMap | getLastParametersQuery () const =0 |
virtual long | getLinksMemoryUsedQuery () const =0 |
virtual long | getMemoryUsedQuery () const =0 |
virtual void | getNodeIdByLabelQuery (const std::string &label, int &id) const =0 |
virtual bool | getNodeInfoQuery (int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps) const =0 |
virtual long | getNodesMemoryUsedQuery () const =0 |
virtual long | getStatisticsMemoryUsedQuery () const =0 |
virtual std::map< std::string, float > | getStatisticsQuery (int nodeId, double &stamp, std::vector< int > *wmState) const =0 |
virtual int | getTotalDictionarySizeQuery () const =0 |
virtual int | getTotalNodesSizeQuery () const =0 |
virtual long | getUserDataMemoryUsedQuery () const =0 |
virtual void | getWeightQuery (int signatureId, int &weight) const =0 |
virtual long | getWordsMemoryUsedQuery () const =0 |
virtual bool | isConnectedQuery () const =0 |
virtual cv::Mat | load2DMapQuery (float &xMin, float &yMin, float &cellSize) const =0 |
virtual void | loadLastNodesQuery (std::list< Signature * > &signatures) const =0 |
virtual void | loadLinksQuery (int signatureId, std::map< int, Link > &links, Link::Type type=Link::kUndef) const =0 |
virtual void | loadNodeDataQuery (std::list< Signature * > &signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const =0 |
virtual cv::Mat | loadOptimizedMeshQuery (std::vector< std::vector< std::vector< unsigned int > > > *polygons, std::vector< std::vector< Eigen::Vector2f > > *texCoords, cv::Mat *textures) const =0 |
virtual std::map< int, Transform > | loadOptimizedPosesQuery (Transform *lastlocalizationPose) const =0 |
virtual cv::Mat | loadPreviewImageQuery () const =0 |
virtual void | loadQuery (VWDictionary *dictionary, bool lastStateOnly=true) const =0 |
virtual void | loadSignaturesQuery (const std::list< int > &ids, std::list< Signature * > &signatures) const =0 |
virtual void | loadWordsQuery (const std::set< int > &wordIds, std::list< VisualWord * > &vws) const =0 |
virtual void | save2DMapQuery (const cv::Mat &map, float xMin, float yMin, float cellSize) const =0 |
virtual void | saveOptimizedMeshQuery (const cv::Mat &cloud, const std::vector< std::vector< std::vector< unsigned int > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, const cv::Mat &textures) const =0 |
virtual void | saveOptimizedPosesQuery (const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const =0 |
virtual void | savePreviewImageQuery (const cv::Mat &image) const =0 |
virtual void | saveQuery (const std::list< Signature * > &signatures)=0 |
virtual void | saveQuery (const std::list< VisualWord * > &words) const =0 |
virtual void | updateDepthImageQuery (int nodeId, const cv::Mat &image) const =0 |
virtual void | updateLinkQuery (const Link &link) const =0 |
virtual void | updateOccupancyGridQuery (int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewpoint) const =0 |
virtual void | updateQuery (const std::list< Signature * > &signatures, bool updateTimestamp) const =0 |
virtual void | updateQuery (const std::list< VisualWord * > &words, bool updateTimestamp) const =0 |
Private Member Functions | |
virtual void | mainLoop () |
void | saveOrUpdate (const std::vector< Signature * > &signatures) |
void | saveOrUpdate (const std::vector< VisualWord * > &words) const |
Private Attributes | |
USemaphore | _addSem |
UMutex | _dbSafeAccessMutex |
double | _emptyTrashesTime |
bool | _timestampUpdate |
UMutex | _transactionMutex |
UMutex | _trashesMutex |
std::map< int, Signature * > | _trashSignatures |
std::map< int, VisualWord * > | _trashVisualWords |
std::string | _url |
Definition at line 62 of file DBDriver.h.
rtabmap::DBDriver::~DBDriver | ( | ) | [virtual] |
Definition at line 54 of file DBDriver.cpp.
rtabmap::DBDriver::DBDriver | ( | const ParametersMap & | parameters = ParametersMap() | ) | [protected] |
Definition at line 47 of file DBDriver.cpp.
void rtabmap::DBDriver::addInfoAfterRun | ( | int | stMemSize, |
int | lastSignAdded, | ||
int | processMemUsed, | ||
int | databaseMemUsed, | ||
int | dictionarySize, | ||
const ParametersMap & | parameters | ||
) | const |
Definition at line 992 of file DBDriver.cpp.
void rtabmap::DBDriver::addLink | ( | const Link & | link | ) |
Definition at line 467 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::addLinkQuery | ( | const Link & | link | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::addStatistics | ( | const Statistics & | statistics | ) | const |
Definition at line 1042 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::addStatisticsQuery | ( | const Statistics & | statistics | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::asyncSave | ( | Signature * | s | ) |
Definition at line 382 of file DBDriver.cpp.
void rtabmap::DBDriver::asyncSave | ( | VisualWord * | vw | ) |
Definition at line 395 of file DBDriver.cpp.
void rtabmap::DBDriver::beginTransaction | ( | ) | const |
Definition at line 290 of file DBDriver.cpp.
void rtabmap::DBDriver::closeConnection | ( | bool | save = true , |
const std::string & | outputUrl = "" |
||
) |
Definition at line 64 of file DBDriver.cpp.
void rtabmap::DBDriver::commit | ( | ) | const |
Definition at line 297 of file DBDriver.cpp.
virtual bool rtabmap::DBDriver::connectDatabaseQuery | ( | const std::string & | url, |
bool | overwritten = false |
||
) | [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
DBDriver * rtabmap::DBDriver::create | ( | const ParametersMap & | parameters = ParametersMap() | ) | [static] |
Definition at line 41 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::disconnectDatabaseQuery | ( | bool | save = true , |
const std::string & | outputUrl = "" |
||
) | [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::emptyTrashes | ( | bool | async = false | ) |
Definition at line 311 of file DBDriver.cpp.
void rtabmap::DBDriver::executeNoResult | ( | const std::string & | sql | ) | const |
Definition at line 304 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::executeNoResultQuery | ( | const std::string & | sql | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::generateGraph | ( | const std::string & | fileName, |
const std::set< int > & | ids = std::set<int>() , |
||
const std::map< int, Signature * > & | otherSignatures = std::map<int, Signature *>() |
||
) |
Definition at line 1123 of file DBDriver.cpp.
void rtabmap::DBDriver::getAllLabels | ( | std::map< int, std::string > & | labels | ) | const |
Definition at line 973 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::getAllLabelsQuery | ( | std::map< int, std::string > & | labels | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getAllLinks | ( | std::multimap< int, Link > & | links, |
bool | ignoreNullLinks = true |
||
) | const |
Definition at line 852 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::getAllLinksQuery | ( | std::multimap< int, Link > & | links, |
bool | ignoreNullLinks | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getAllNodeIds | ( | std::set< int > & | ids, |
bool | ignoreChildren = false , |
||
bool | ignoreBadSignatures = false |
||
) | const |
Definition at line 813 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::getAllNodeIdsQuery | ( | std::set< int > & | ids, |
bool | ignoreChildren, | ||
bool | ignoreBadSignatures | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
std::map< int, std::pair< std::map< std::string, float >, double > > rtabmap::DBDriver::getAllStatistics | ( | ) | const |
Definition at line 257 of file DBDriver.cpp.
virtual std::map<int, std::pair<std::map<std::string, float>, double> > rtabmap::DBDriver::getAllStatisticsQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
std::map< int, std::vector< int > > rtabmap::DBDriver::getAllStatisticsWmStates | ( | ) | const |
Definition at line 266 of file DBDriver.cpp.
virtual std::map<int, std::vector<int> > rtabmap::DBDriver::getAllStatisticsWmStatesQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
bool rtabmap::DBDriver::getCalibration | ( | int | signatureId, |
std::vector< CameraModel > & | models, | ||
StereoCameraModel & | stereoModel | ||
) | const |
Definition at line 677 of file DBDriver.cpp.
virtual bool rtabmap::DBDriver::getCalibrationQuery | ( | int | signatureId, |
std::vector< CameraModel > & | models, | ||
StereoCameraModel & | stereoModel | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getCalibrationsMemoryUsed | ( | ) | const |
Definition at line 151 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getCalibrationsMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
std::string rtabmap::DBDriver::getDatabaseVersion | ( | ) | const |
Definition at line 275 of file DBDriver.cpp.
virtual bool rtabmap::DBDriver::getDatabaseVersionQuery | ( | std::string & | version | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getDepthImagesMemoryUsed | ( | ) | const |
Definition at line 143 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getDepthImagesMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
double rtabmap::DBDriver::getEmptyTrashesTime | ( | ) | const [inline] |
Definition at line 80 of file DBDriver.h.
long rtabmap::DBDriver::getFeaturesMemoryUsed | ( | ) | const |
Definition at line 191 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getFeaturesMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getGridsMemoryUsed | ( | ) | const |
Definition at line 159 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getGridsMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getImagesMemoryUsed | ( | ) | const |
Definition at line 135 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getImagesMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getInvertedIndexNi | ( | int | signatureId, |
int & | ni | ||
) | const |
Definition at line 918 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::getInvertedIndexNiQuery | ( | int | signatureId, |
int & | ni | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
bool rtabmap::DBDriver::getLaserScanInfo | ( | int | signatureId, |
LaserScan & | info | ||
) | const |
Definition at line 703 of file DBDriver.cpp.
virtual bool rtabmap::DBDriver::getLaserScanInfoQuery | ( | int | signatureId, |
LaserScan & | info | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getLaserScansMemoryUsed | ( | ) | const |
Definition at line 167 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getLaserScansMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
int rtabmap::DBDriver::getLastDictionarySize | ( | ) | const |
Definition at line 215 of file DBDriver.cpp.
virtual int rtabmap::DBDriver::getLastDictionarySizeQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual void rtabmap::DBDriver::getLastIdQuery | ( | const std::string & | tableName, |
int & | id | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getLastNodeId | ( | int & | id | ) | const |
Definition at line 879 of file DBDriver.cpp.
int rtabmap::DBDriver::getLastNodesSize | ( | ) | const |
Definition at line 207 of file DBDriver.cpp.
virtual int rtabmap::DBDriver::getLastNodesSizeQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
Definition at line 239 of file DBDriver.cpp.
virtual ParametersMap rtabmap::DBDriver::getLastParametersQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getLastWordId | ( | int & | id | ) | const |
Definition at line 903 of file DBDriver.cpp.
long rtabmap::DBDriver::getLinksMemoryUsed | ( | ) | const |
Definition at line 127 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getLinksMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getMemoryUsed | ( | ) | const |
Definition at line 110 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getNodeData | ( | int | signatureId, |
SensorData & | data, | ||
bool | images = true , |
||
bool | scan = true , |
||
bool | userData = true , |
||
bool | occupancyGrid = true |
||
) | const |
Definition at line 642 of file DBDriver.cpp.
void rtabmap::DBDriver::getNodeIdByLabel | ( | const std::string & | label, |
int & | id | ||
) | const |
Definition at line 938 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::getNodeIdByLabelQuery | ( | const std::string & | label, |
int & | id | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
bool rtabmap::DBDriver::getNodeInfo | ( | int | signatureId, |
Transform & | pose, | ||
int & | mapId, | ||
int & | weight, | ||
std::string & | label, | ||
double & | stamp, | ||
Transform & | groundTruthPose, | ||
std::vector< float > & | velocity, | ||
GPS & | gps | ||
) | const |
Definition at line 727 of file DBDriver.cpp.
virtual bool rtabmap::DBDriver::getNodeInfoQuery | ( | int | signatureId, |
Transform & | pose, | ||
int & | mapId, | ||
int & | weight, | ||
std::string & | label, | ||
double & | stamp, | ||
Transform & | groundTruthPose, | ||
std::vector< float > & | velocity, | ||
GPS & | gps | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getNodesMemoryUsed | ( | ) | const |
Definition at line 119 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getNodesMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
std::map< std::string, float > rtabmap::DBDriver::getStatistics | ( | int | nodeId, |
double & | stamp, | ||
std::vector< int > * | wmState = 0 |
||
) | const |
Definition at line 248 of file DBDriver.cpp.
long rtabmap::DBDriver::getStatisticsMemoryUsed | ( | ) | const |
Definition at line 199 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getStatisticsMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual std::map<std::string, float> rtabmap::DBDriver::getStatisticsQuery | ( | int | nodeId, |
double & | stamp, | ||
std::vector< int > * | wmState | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
int rtabmap::DBDriver::getTotalDictionarySize | ( | ) | const |
Definition at line 231 of file DBDriver.cpp.
virtual int rtabmap::DBDriver::getTotalDictionarySizeQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
int rtabmap::DBDriver::getTotalNodesSize | ( | ) | const |
Definition at line 223 of file DBDriver.cpp.
virtual int rtabmap::DBDriver::getTotalNodesSizeQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
const std::string& rtabmap::DBDriver::getUrl | ( | ) | const [inline] |
Definition at line 72 of file DBDriver.h.
long rtabmap::DBDriver::getUserDataMemoryUsed | ( | ) | const |
Definition at line 175 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getUserDataMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::getWeight | ( | int | signatureId, |
int & | weight | ||
) | const |
Definition at line 793 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::getWeightQuery | ( | int | signatureId, |
int & | weight | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
long rtabmap::DBDriver::getWordsMemoryUsed | ( | ) | const |
Definition at line 183 of file DBDriver.cpp.
virtual long rtabmap::DBDriver::getWordsMemoryUsedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
bool rtabmap::DBDriver::isConnected | ( | ) | const |
Definition at line 100 of file DBDriver.cpp.
virtual bool rtabmap::DBDriver::isConnectedQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual bool rtabmap::DBDriver::isInMemory | ( | ) | const [inline, virtual] |
Reimplemented in rtabmap::DBDriverSqlite3.
Definition at line 71 of file DBDriver.h.
void rtabmap::DBDriver::load | ( | VWDictionary * | dictionary, |
bool | lastStateOnly = true |
||
) | const |
Definition at line 514 of file DBDriver.cpp.
cv::Mat rtabmap::DBDriver::load2DMap | ( | float & | xMin, |
float & | yMin, | ||
float & | cellSize | ||
) | const |
Definition at line 1085 of file DBDriver.cpp.
virtual cv::Mat rtabmap::DBDriver::load2DMapQuery | ( | float & | xMin, |
float & | yMin, | ||
float & | cellSize | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::loadLastNodes | ( | std::list< Signature * > & | signatures | ) | const |
Definition at line 521 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::loadLastNodesQuery | ( | std::list< Signature * > & | signatures | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::loadLinks | ( | int | signatureId, |
std::map< int, Link > & | links, | ||
Link::Type | type = Link::kUndef |
||
) | const |
Definition at line 763 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::loadLinksQuery | ( | int | signatureId, |
std::map< int, Link > & | links, | ||
Link::Type | type = Link::kUndef |
||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::loadNodeData | ( | std::list< Signature * > & | signatures, |
bool | images = true , |
||
bool | scan = true , |
||
bool | userData = true , |
||
bool | occupancyGrid = true |
||
) | const |
Definition at line 622 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::loadNodeDataQuery | ( | std::list< Signature * > & | signatures, |
bool | images = true , |
||
bool | scan = true , |
||
bool | userData = true , |
||
bool | occupancyGrid = true |
||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
cv::Mat rtabmap::DBDriver::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 1108 of file DBDriver.cpp.
virtual cv::Mat rtabmap::DBDriver::loadOptimizedMeshQuery | ( | std::vector< std::vector< std::vector< unsigned int > > > * | polygons, |
std::vector< std::vector< Eigen::Vector2f > > * | texCoords, | ||
cv::Mat * | textures | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
std::map< int, Transform > rtabmap::DBDriver::loadOptimizedPoses | ( | Transform * | lastlocalizationPose | ) | const |
Definition at line 1070 of file DBDriver.cpp.
virtual std::map<int, Transform> rtabmap::DBDriver::loadOptimizedPosesQuery | ( | Transform * | lastlocalizationPose | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
cv::Mat rtabmap::DBDriver::loadPreviewImage | ( | ) | const |
Definition at line 1056 of file DBDriver.cpp.
virtual cv::Mat rtabmap::DBDriver::loadPreviewImageQuery | ( | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual void rtabmap::DBDriver::loadQuery | ( | VWDictionary * | dictionary, |
bool | lastStateOnly = true |
||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::loadSignatures | ( | const std::list< int > & | ids, |
std::list< Signature * > & | signatures, | ||
std::set< int > * | loadedFromTrash = 0 |
||
) |
Definition at line 528 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::loadSignaturesQuery | ( | const std::list< int > & | ids, |
std::list< Signature * > & | signatures | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::loadWords | ( | const std::set< int > & | wordIds, |
std::list< VisualWord * > & | vws | ||
) |
Definition at line 580 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::loadWordsQuery | ( | const std::set< int > & | wordIds, |
std::list< VisualWord * > & | vws | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::mainLoop | ( | ) | [private, virtual] |
Pure virtual method mainLoop(). The inner loop of the thread. This method is called repetitively until the thread is killed. Note that if kill() is called in mainLoopBegin(), mainLoop() is not called, terminating immediately the thread.
Implements UThread.
Definition at line 284 of file DBDriver.cpp.
bool rtabmap::DBDriver::openConnection | ( | const std::string & | url, |
bool | overwritten = false |
||
) |
Definition at line 86 of file DBDriver.cpp.
void rtabmap::DBDriver::parseParameters | ( | const ParametersMap & | parameters | ) | [virtual] |
Reimplemented in rtabmap::DBDriverSqlite3.
Definition at line 60 of file DBDriver.cpp.
void rtabmap::DBDriver::removeLink | ( | int | from, |
int | to | ||
) |
Definition at line 473 of file DBDriver.cpp.
void rtabmap::DBDriver::save2DMap | ( | const cv::Mat & | map, |
float | xMin, | ||
float | yMin, | ||
float | cellSize | ||
) | const |
Definition at line 1078 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::save2DMapQuery | ( | const cv::Mat & | map, |
float | xMin, | ||
float | yMin, | ||
float | cellSize | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::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 1093 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::saveOptimizedMeshQuery | ( | const cv::Mat & | cloud, |
const std::vector< std::vector< std::vector< unsigned int > > > & | polygons, | ||
const std::vector< std::vector< Eigen::Vector2f > > & | texCoords, | ||
const cv::Mat & | textures | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::saveOptimizedPoses | ( | const std::map< int, Transform > & | optimizedPoses, |
const Transform & | lastlocalizationPose | ||
) | const |
Definition at line 1064 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::saveOptimizedPosesQuery | ( | const std::map< int, Transform > & | optimizedPoses, |
const Transform & | lastlocalizationPose | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::saveOrUpdate | ( | const std::vector< Signature * > & | signatures | ) | [private] |
Definition at line 407 of file DBDriver.cpp.
void rtabmap::DBDriver::saveOrUpdate | ( | const std::vector< VisualWord * > & | words | ) | const [private] |
Definition at line 437 of file DBDriver.cpp.
void rtabmap::DBDriver::savePreviewImage | ( | const cv::Mat & | image | ) | const |
Definition at line 1049 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::savePreviewImageQuery | ( | const cv::Mat & | image | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual void rtabmap::DBDriver::saveQuery | ( | const std::list< Signature * > & | signatures | ) | [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual void rtabmap::DBDriver::saveQuery | ( | const std::list< VisualWord * > & | words | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::setTimestampUpdateEnabled | ( | bool | enabled | ) | [inline] |
Definition at line 81 of file DBDriver.h.
void rtabmap::DBDriver::updateDepthImage | ( | int | nodeId, |
const cv::Mat & | image | ||
) |
Definition at line 505 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::updateDepthImageQuery | ( | int | nodeId, |
const cv::Mat & | image | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::updateLink | ( | const Link & | link | ) |
Definition at line 477 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::updateLinkQuery | ( | const Link & | link | ) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
void rtabmap::DBDriver::updateOccupancyGrid | ( | int | nodeId, |
const cv::Mat & | ground, | ||
const cv::Mat & | obstacles, | ||
const cv::Mat & | empty, | ||
float | cellSize, | ||
const cv::Point3f & | viewpoint | ||
) |
Definition at line 483 of file DBDriver.cpp.
virtual void rtabmap::DBDriver::updateOccupancyGridQuery | ( | int | nodeId, |
const cv::Mat & | ground, | ||
const cv::Mat & | obstacles, | ||
const cv::Mat & | empty, | ||
float | cellSize, | ||
const cv::Point3f & | viewpoint | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual void rtabmap::DBDriver::updateQuery | ( | const std::list< Signature * > & | signatures, |
bool | updateTimestamp | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
virtual void rtabmap::DBDriver::updateQuery | ( | const std::list< VisualWord * > & | words, |
bool | updateTimestamp | ||
) | const [protected, pure virtual] |
Implemented in rtabmap::DBDriverSqlite3.
USemaphore rtabmap::DBDriver::_addSem [private] |
Definition at line 288 of file DBDriver.h.
UMutex rtabmap::DBDriver::_dbSafeAccessMutex [private] |
Definition at line 287 of file DBDriver.h.
double rtabmap::DBDriver::_emptyTrashesTime [private] |
Definition at line 289 of file DBDriver.h.
bool rtabmap::DBDriver::_timestampUpdate [private] |
Definition at line 291 of file DBDriver.h.
UMutex rtabmap::DBDriver::_transactionMutex [private] |
Definition at line 283 of file DBDriver.h.
UMutex rtabmap::DBDriver::_trashesMutex [private] |
Definition at line 286 of file DBDriver.h.
std::map<int, Signature *> rtabmap::DBDriver::_trashSignatures [private] |
Definition at line 284 of file DBDriver.h.
std::map<int, VisualWord *> rtabmap::DBDriver::_trashVisualWords [private] |
Definition at line 285 of file DBDriver.h.
std::string rtabmap::DBDriver::_url [private] |
Definition at line 290 of file DBDriver.h.