|
| DBDriverSqlite3 (const ParametersMap ¶meters=ParametersMap()) |
|
virtual bool | isInMemory () const |
|
virtual void | parseParameters (const ParametersMap ¶meters) |
|
void | setCacheSize (unsigned int cacheSize) |
|
void | setDbInMemory (bool dbInMemory) |
|
void | setJournalMode (int journalMode) |
|
void | setSynchronous (int synchronous) |
|
void | setTempStore (int tempStore) |
|
virtual | ~DBDriverSqlite3 () |
|
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, bool saveWmState) 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, bool withLandmarks=false) 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 | getLastMapId (int &mapId) const |
|
void | getLastNodeId (int &id) const |
|
void | getLastNodeIds (std::set< int > &ids) const |
|
int | getLastNodesSize () const |
|
ParametersMap | getLastParameters () const |
|
void | getLastWordId (int &id) const |
|
long | getLinksMemoryUsed () const |
|
unsigned 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, EnvSensors &sensors) const |
|
long | getNodesMemoryUsed () const |
|
void | getNodesObservingLandmark (int landmarkId, std::map< int, Link > &nodes) const |
|
std::map< std::string, float > | getStatistics (int nodeId, double &stamp, std::vector< int > *wmState=0) const |
|
long | getStatisticsMemoryUsed () const |
|
const std::string & | getTargetVersion () 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 |
|
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::multimap< int, Link > &links, Link::Type type=Link::kUndef) const |
|
void | loadNodeData (Signature *signature, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) 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< RTABMAP_PCL_INDEX > > > *polygons=0, std::vector< std::vector< Eigen::Vector2f > > *texCoords=0, cv::Mat *textures=0) const |
|
std::map< int, Transform > | loadOptimizedPoses (Transform *lastlocalizationPose=0) const |
|
cv::Mat | loadPreviewImage () const |
|
Signature * | loadSignature (int id, bool *loadedFromTrash=0) |
|
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) |
|
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< RTABMAP_PCL_INDEX > > > &polygons=std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > >(), 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 | updateLaserScan (int nodeId, const LaserScan &scan) |
|
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 () |
|
Handle | getThreadHandle () const |
|
unsigned long | getThreadId () const |
|
bool | isCreating () const |
|
bool | isIdle () const |
|
bool | isKilled () const |
|
bool | isRunning () const |
|
void | join (bool killFirst=false) |
|
void | kill () |
|
void | setAffinity (int cpu=0) |
|
void | setPriority (Priority priority) |
|
void | start () |
|
| UThread (Priority priority=kPNormal) |
|
virtual | ~UThread () |
|
int | Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
|
int | Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
|
int | Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
|
int | Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
|
virtual | ~UThreadC () |
|
virtual | ~UThreadC () |
|
|
virtual void | addLinkQuery (const Link &link) const |
|
virtual void | addStatisticsQuery (const Statistics &statistics, bool saveWmState) const |
|
virtual bool | connectDatabaseQuery (const std::string &url, bool overwritten=false) |
|
virtual void | disconnectDatabaseQuery (bool save=true, const std::string &outputUrl="") |
|
virtual void | executeNoResultQuery (const std::string &sql) const |
|
virtual void | getAllLabelsQuery (std::map< int, std::string > &labels) const |
|
virtual void | getAllLinksQuery (std::multimap< int, Link > &links, bool ignoreNullLinks, bool withLandmarks) const |
|
virtual void | getAllNodeIdsQuery (std::set< int > &ids, bool ignoreChildren, bool ignoreBadSignatures) const |
|
virtual std::map< int, std::pair< std::map< std::string, float >, double > > | getAllStatisticsQuery () const |
|
virtual std::map< int, std::vector< int > > | getAllStatisticsWmStatesQuery () const |
|
virtual bool | getCalibrationQuery (int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const |
|
virtual long | getCalibrationsMemoryUsedQuery () const |
|
virtual bool | getDatabaseVersionQuery (std::string &version) const |
|
virtual long | getDepthImagesMemoryUsedQuery () const |
|
virtual long | getFeaturesMemoryUsedQuery () const |
|
virtual long | getGridsMemoryUsedQuery () const |
|
virtual long | getImagesMemoryUsedQuery () const |
|
virtual void | getInvertedIndexNiQuery (int signatureId, int &ni) const |
|
virtual bool | getLaserScanInfoQuery (int signatureId, LaserScan &info) const |
|
virtual long | getLaserScansMemoryUsedQuery () const |
|
virtual int | getLastDictionarySizeQuery () const |
|
virtual void | getLastIdQuery (const std::string &tableName, int &id, const std::string &fieldName="id") const |
|
virtual void | getLastNodeIdsQuery (std::set< int > &ids) const |
|
virtual int | getLastNodesSizeQuery () const |
|
virtual ParametersMap | getLastParametersQuery () const |
|
virtual long | getLinksMemoryUsedQuery () const |
|
virtual unsigned long | getMemoryUsedQuery () const |
|
virtual void | getNodeIdByLabelQuery (const std::string &label, int &id) const |
|
virtual bool | getNodeInfoQuery (int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps, EnvSensors &sensors) const |
|
virtual long | getNodesMemoryUsedQuery () const |
|
virtual void | getNodesObservingLandmarkQuery (int landmarkId, std::map< int, Link > &nodes) const |
|
virtual long | getStatisticsMemoryUsedQuery () const |
|
virtual std::map< std::string, float > | getStatisticsQuery (int nodeId, double &stamp, std::vector< int > *wmState) const |
|
virtual int | getTotalDictionarySizeQuery () const |
|
virtual int | getTotalNodesSizeQuery () const |
|
virtual long | getUserDataMemoryUsedQuery () const |
|
virtual void | getWeightQuery (int signatureId, int &weight) const |
|
virtual long | getWordsMemoryUsedQuery () const |
|
virtual bool | isConnectedQuery () const |
|
virtual cv::Mat | load2DMapQuery (float &xMin, float &yMin, float &cellSize) const |
|
virtual void | loadLastNodesQuery (std::list< Signature * > &signatures) const |
|
virtual void | loadLinksQuery (int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const |
|
virtual void | loadNodeDataQuery (std::list< Signature * > &signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const |
|
virtual cv::Mat | loadOptimizedMeshQuery (std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > *polygons, std::vector< std::vector< Eigen::Vector2f > > *texCoords, cv::Mat *textures) const |
|
virtual std::map< int, Transform > | loadOptimizedPosesQuery (Transform *lastlocalizationPose=0) const |
|
virtual cv::Mat | loadPreviewImageQuery () const |
|
virtual void | loadQuery (VWDictionary *dictionary, bool lastStateOnly=true) const |
|
virtual void | loadSignaturesQuery (const std::list< int > &ids, std::list< Signature * > &signatures) const |
|
virtual void | loadWordsQuery (const std::set< int > &wordIds, std::list< VisualWord * > &vws) const |
|
virtual void | save2DMapQuery (const cv::Mat &map, float xMin, float yMin, float cellSize) const |
|
virtual void | saveOptimizedMeshQuery (const cv::Mat &cloud, const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, const cv::Mat &textures) const |
|
virtual void | saveOptimizedPosesQuery (const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const |
|
virtual void | savePreviewImageQuery (const cv::Mat &image) const |
|
virtual void | saveQuery (const std::list< Signature * > &signatures) |
|
virtual void | saveQuery (const std::list< VisualWord * > &words) const |
|
virtual void | updateDepthImageQuery (int nodeId, const cv::Mat &image) const |
|
void | updateLaserScanQuery (int nodeId, const LaserScan &scan) const |
|
virtual void | updateLinkQuery (const Link &link) const |
|
virtual void | updateOccupancyGridQuery (int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewpoint) const |
|
virtual void | updateQuery (const std::list< Signature * > &signatures, bool updateTimestamp) const |
|
virtual void | updateQuery (const std::list< VisualWord * > &words, bool updateTimestamp) const |
|
| DBDriver (const ParametersMap ¶meters=ParametersMap()) |
|
| UThreadC () |
|
| UThreadC () |
|
|
void | loadLinksQuery (std::list< Signature * > &signatures) const |
|
int | loadOrSaveDb (sqlite3 *pInMemory, const std::string &fileName, int isSave) const |
|
std::string | queryStepDepth () const |
|
std::string | queryStepDepthUpdate () const |
|
std::string | queryStepGlobalDescriptor () const |
|
std::string | queryStepImage () const |
|
std::string | queryStepKeypoint () const |
|
std::string | queryStepLink () const |
|
std::string | queryStepLinkUpdate () const |
|
std::string | queryStepNode () const |
|
std::string | queryStepOccupancyGridUpdate () const |
|
std::string | queryStepScanUpdate () const |
|
std::string | queryStepSensorData () const |
|
std::string | queryStepWordsChanged () const |
|
void | stepDepth (sqlite3_stmt *ppStmt, const SensorData &sensorData) const |
|
void | stepDepthUpdate (sqlite3_stmt *ppStmt, int nodeId, const cv::Mat &imageCompressed) const |
|
void | stepGlobalDescriptor (sqlite3_stmt *ppStmt, int nodeId, const GlobalDescriptor &descriptor) const |
|
void | stepImage (sqlite3_stmt *ppStmt, int id, const cv::Mat &imageBytes) const |
|
void | stepKeypoint (sqlite3_stmt *ppStmt, int nodeID, int wordId, const cv::KeyPoint &kp, const cv::Point3f &pt, const cv::Mat &descriptor) const |
|
void | stepLink (sqlite3_stmt *ppStmt, const Link &link) const |
|
void | stepNode (sqlite3_stmt *ppStmt, const Signature *s) const |
|
void | stepOccupancyGridUpdate (sqlite3_stmt *ppStmt, int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewpoint) const |
|
void | stepScanUpdate (sqlite3_stmt *ppStmt, int nodeId, const LaserScan &image) const |
|
void | stepSensorData (sqlite3_stmt *ppStmt, const SensorData &sensorData) const |
|
void | stepWordsChanged (sqlite3_stmt *ppStmt, int signatureId, int oldWordId, int newWordId) const |
|