43 #include <opencv2/core/core.hpp> 44 #include <opencv2/features2d/features2d.hpp> 45 #include <pcl/pcl_config.h> 56 class RegistrationInfo;
57 class RegistrationIcp;
58 class RegistrationVis;
74 virtual void parseParameters(
const ParametersMap & parameters);
80 const cv::Mat & covariance,
81 const std::vector<float> & velocity = std::vector<float>(),
83 bool init(
const std::string & dbUrl,
84 bool dbOverwritten =
false,
86 bool postInitClosingEvents =
false);
87 void close(
bool databaseSaved =
true,
bool postInitClosingEvents =
false,
const std::string & ouputDatabasePath =
"");
88 std::map<int, float> computeLikelihood(
const Signature * signature,
89 const std::list<int> & ids);
90 int incrementMapId(std::map<int, int> * reducedIds = 0);
91 void updateAge(
int signatureId);
93 std::list<int> forget(
const std::set<int> & ignoredIds = std::set<int>());
94 std::set<int> reactivateSignatures(
const std::list<int> & ids,
unsigned int maxLoaded,
double & timeDbAccess);
97 void saveStatistics(
const Statistics & statistics,
bool saveWMState);
98 void savePreviewImage(
const cv::Mat & image)
const;
99 cv::Mat loadPreviewImage()
const;
100 void saveOptimizedPoses(
const std::map<int, Transform> & optimizedPoses,
const Transform & lastlocalizationPose)
const;
101 std::map<int, Transform> loadOptimizedPoses(
Transform * lastlocalizationPose)
const;
102 void save2DMap(
const cv::Mat & map,
float xMin,
float yMin,
float cellSize)
const;
103 cv::Mat load2DMap(
float & xMin,
float & yMin,
float & cellSize)
const;
104 void saveOptimizedMesh(
105 const cv::Mat & cloud,
106 const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons = std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > >(),
107 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
108 const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords = std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > >(),
110 const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(),
112 const cv::Mat & textures = cv::Mat())
const;
113 cv::Mat loadOptimizedMesh(
114 std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons = 0,
115 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
116 std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords = 0,
118 std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
120 cv::Mat * textures = 0)
const;
122 void joinTrashThread();
123 bool addLink(
const Link & link,
bool addInDatabase =
false);
124 void updateLink(
const Link & link,
bool updateInDatabase =
false);
125 void removeAllVirtualLinks();
126 void removeVirtualLinks(
int signatureId);
127 std::map<int, int> getNeighborsId(
130 int maxCheckedInDatabase = -1,
131 bool incrementMarginOnLoop =
false,
132 bool ignoreLoopIds =
false,
133 bool ignoreIntermediateNodes =
false,
134 bool ignoreLocalSpaceLoopIds =
false,
135 const std::set<int> & nodesSet = std::set<int>(),
136 double * dbAccessTime = 0)
const;
137 std::map<int, float> getNeighborsIdRadius(
140 const std::map<int, Transform> & optimizedPoses,
141 int maxGraphDepth)
const;
142 void deleteLocation(
int locationId, std::list<int> * deletedWords = 0);
143 void saveLocationData(
int locationId);
144 void removeLink(
int idA,
int idB);
145 void removeRawData(
int id,
bool image =
true,
bool scan =
true,
bool userData =
true);
149 const std::set<int> &
getStMem()
const {
return _stMem;}
151 std::multimap<int, Link> getNeighborLinks(
int signatureId,
152 bool lookInDatabase =
false)
const;
153 std::multimap<int, Link> getLoopClosureLinks(
int signatureId,
154 bool lookInDatabase =
false)
const;
155 std::multimap<int, Link> getLinks(
int signatureId,
156 bool lookInDatabase =
false,
157 bool withLandmarks =
false)
const;
158 std::multimap<int, Link> getAllLinks(
bool lookInDatabase,
bool ignoreNullLinks =
true,
bool withLandmarks =
false)
const;
161 std::map<int, int> getWeights()
const;
162 int getLastSignatureId()
const;
163 const Signature * getLastWorkingSignature()
const;
164 std::map<int, Link> getNodesObservingLandmark(
int landmarkId,
bool lookInDatabase)
const;
165 int getSignatureIdByLabel(
const std::string & label,
bool lookInDatabase =
true)
const;
166 bool labelSignature(
int id,
const std::string & label);
167 const std::map<int, std::string> &
getAllLabels()
const {
return _labels;}
178 bool setUserData(
int id,
const cv::Mat & data);
179 int getDatabaseMemoryUsed()
const;
180 std::string getDatabaseVersion()
const;
181 std::string getDatabaseUrl()
const;
182 double getDbSavingTime()
const;
183 int getMapId(
int id,
bool lookInDatabase =
false)
const;
184 Transform getOdomPose(
int signatureId,
bool lookInDatabase =
false)
const;
185 Transform getGroundTruthPose(
int signatureId,
bool lookInDatabase =
false)
const;
187 void getGPS(
int id,
GPS & gps,
Transform & offsetENU,
bool lookInDatabase,
int maxGraphDepth = 0)
const;
188 bool getNodeInfo(
int signatureId,
195 std::vector<float> & velocity,
198 bool lookInDatabase =
false)
const;
199 cv::Mat getImageCompressed(
int signatureId)
const;
200 SensorData getNodeData(
int locationId,
bool images,
bool scan,
bool userData,
bool occupancyGrid)
const;
201 void getNodeWordsAndGlobalDescriptors(
int nodeId,
202 std::multimap<int, int> & words,
203 std::vector<cv::KeyPoint> & wordsKpts,
204 std::vector<cv::Point3f> & words3,
205 cv::Mat & wordsDescriptors,
206 std::vector<GlobalDescriptor> & globalDescriptors)
const;
207 void getNodeCalibration(
int nodeId,
208 std::vector<CameraModel> & models,
209 std::vector<StereoCameraModel> & stereoModels)
const;
210 std::set<int> getAllSignatureIds(
bool ignoreChildren =
true)
const;
214 const Signature * getSignature(
int id)
const;
215 bool isInSTM(
int signatureId)
const {
return _stMem.find(signatureId) != _stMem.end();}
216 bool isInWM(
int signatureId)
const {
return _workingMem.find(signatureId) != _workingMem.end();}
217 bool isInLTM(
int signatureId)
const {
return !this->isInSTM(signatureId) && !this->isInWM(signatureId);}
225 void dumpMemoryTree(
const char * fileNameTree)
const;
226 virtual void dumpMemory(std::string directory)
const;
227 virtual void dumpSignatures(
const char * fileNameSign,
bool words3D)
const;
228 void dumpDictionary(
const char * fileNameRef,
const char * fileNameDesc)
const;
229 unsigned long getMemoryUsed()
const;
231 void generateGraph(
const std::string & fileName,
const std::set<int> & ids = std::set<int>());
232 int cleanupLocalGrids(
233 const std::map<int, Transform> & poses,
239 bool filterScans =
false);
245 void getMetricConstraints(
246 const std::set<int> & ids,
247 std::map<int, Transform> & poses,
248 std::multimap<int, Link> & links,
249 bool lookInDatabase =
false,
250 bool landmarksAdded =
false);
258 const std::map<int, Transform> & poses,
263 void addSignatureToStm(
Signature * signature,
const cv::Mat & covariance);
265 void loadDataFromDb(
bool postInitClosingEvents);
266 void moveToTrash(
Signature * s,
bool keepLinkedToGraph =
true, std::list<int> * deletedWords = 0);
268 void moveSignatureToWMFromSTM(
int id,
int * reducedTo = 0);
269 void addSignatureToWmFromLTM(
Signature * signature);
271 std::list<Signature *> getRemovableSignatures(
int count,
272 const std::set<int> & ignoredIds = std::set<int>());
276 bool rehearsalMerge(
int oldId,
int newId);
278 const std::map<int, Signature*> &
getSignatures()
const {
return _signatures;}
287 void disableWordsRef(
int signatureId);
288 void enableWordsRef(
const std::list<int> & signatureIds);
289 void cleanUnusedWords();
290 int getNi(
int signatureId)
const;
OccupancyGrid * _occupancy
virtual const ParametersMap & getParameters() const
Signature * _lastSignature
float _similarityThreshold
bool allNodesInWM() const
bool _localizationDataSaved
float getSimilarityThreshold() const
bool _imagesAlreadyRectified
bool memoryChanged() const
const std::set< int > & getStMem() const
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
bool isIncremental() const
bool _transferSortingByWeightId
std::map< int, float > _landmarksSize
bool _tfIdfLikelihoodUsed
bool _compressionParallelized
std::map< std::string, std::string > ParametersMap
const Feature2D * getFeature2D() const
Registration * _registrationPipeline
const std::map< int, Signature * > & getSignatures() const
bool isBinDataKept() const
bool _reextractLoopClosureFeatures
const std::map< int, std::string > & getAllLabels() const
bool isInLTM(int signatureId) const
std::map< int, std::string > _labels
Wrappers of STL for convenient functions.
float _laserScanGroundNormalsUp
unsigned int _imagePreDecimation
unsigned int _imagePostDecimation
bool isOdomGravityUsed() const
float _laserScanDownsampleStepSize
bool _localBundleOnLoopClosure
RegistrationIcp * _registrationIcpMulti
static const int kIdStart
bool isIDsGenerated() const
bool _createOccupancyGrid
int getLastGlobalLoopClosureId() const
const std::vector< double > & getOdomMaxInf() const
static const int kIdInvalid
float _laserScanVoxelSize
bool _rectifyOnlyFeatures
std::map< int, Transform > _groundTruths
bool _saveIntermediateNodeData
std::vector< CameraModel > _rectCameraModels
const std::map< int, Transform > & getGroundTruths() const
bool isInWM(int signatureId) const
bool _notLinkedNodesKeptInDb
const std::map< int, double > & getWorkingMem() const
bool _badSignaturesIgnored
std::string _rgbCompressionFormat
bool _useOdometryFeatures
static const int kIdVirtual
MarkerDetector * _markerDetector
float _rehearsalMaxDistance
std::vector< StereoCameraModel > _rectStereoCameraModels
bool isGraphReduced() const
bool _idUpdatedToNewOneRehearsal
bool isLocalizationDataSaved() const
RegistrationVis * _registrationVis
float _laserScanNormalRadius
std::map< EnvSensor::Type, EnvSensor > EnvSensors
ParametersMap parameters_
std::map< int, std::set< int > > _landmarksIndex
std::map< int, Signature * > _signatures
std::vector< double > _odomMaxInf
bool _rehearsalWeightIgnoredWhileMoving
bool _covOffDiagonalIgnored
int _lastGlobalLoopClosureId
int getMaxStMemSize() const
bool isInSTM(int signatureId) const
std::map< int, double > _workingMem
const std::map< int, std::set< int > > & getLandmarksIndex() const