DBReader.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "rtabmap/core/DBReader.h"
29 #include "rtabmap/core/DBDriver.h"
30 
32 #include <rtabmap/utilite/UFile.h>
33 #include <rtabmap/utilite/UStl.h>
36 
40 #include "rtabmap/core/util3d.h"
42 
43 namespace rtabmap {
44 
45 DBReader::DBReader(const std::string & databasePath,
46  float frameRate,
47  bool odometryIgnored,
48  bool ignoreGoalDelay,
49  bool goalsIgnored,
50  int startId,
51  int cameraIndex,
52  int stopId) :
53  Camera(frameRate),
54  _paths(uSplit(databasePath, ';')),
55  _odometryIgnored(odometryIgnored),
56  _ignoreGoalDelay(ignoreGoalDelay),
57  _goalsIgnored(goalsIgnored),
58  _startId(startId),
59  _stopId(stopId),
60  _cameraIndex(cameraIndex),
61  _dbDriver(0),
62  _currentId(_ids.end()),
63  _previousMapId(-1),
64  _previousStamp(0),
65  _previousMapID(0),
66  _calibrated(false)
67 {
68  if(_stopId>0 && _stopId<_startId)
69  {
70  _stopId = _startId;
71  }
72 }
73 
74 DBReader::DBReader(const std::list<std::string> & databasePaths,
75  float frameRate,
76  bool odometryIgnored,
77  bool ignoreGoalDelay,
78  bool goalsIgnored,
79  int startId,
80  int cameraIndex,
81  int stopId) :
82  Camera(frameRate),
83  _paths(databasePaths),
84  _odometryIgnored(odometryIgnored),
85  _ignoreGoalDelay(ignoreGoalDelay),
86  _goalsIgnored(goalsIgnored),
87  _startId(startId),
88  _stopId(stopId),
89  _cameraIndex(cameraIndex),
90  _dbDriver(0),
91  _currentId(_ids.end()),
92  _previousMapId(-1),
93  _previousStamp(0),
94  _previousMapID(0),
96 {
97  if(_stopId>0 && _stopId<_startId)
98  {
99  _stopId = _startId;
100  }
101 }
102 
104 {
105  if(_dbDriver)
106  {
108  delete _dbDriver;
109  }
110 }
111 
113  const std::string & calibrationFolder,
114  const std::string & cameraName)
115 {
116  if(_dbDriver)
117  {
119  delete _dbDriver;
120  _dbDriver = 0;
121  }
122  _ids.clear();
123  _currentId=_ids.end();
124  _previousMapId = -1;
125  _previousInfMatrix = cv::Mat();
126  _previousStamp = 0;
127  _previousMapID = 0;
128  _calibrated = false;
129 
130  if(_paths.size() == 0)
131  {
132  UERROR("No database path set...");
133  return false;
134  }
135 
136  std::string path = _paths.front();
137  if(!UFile::exists(path))
138  {
139  UERROR("Database path does not exist (%s)", path.c_str());
140  return false;
141  }
142 
143  rtabmap::ParametersMap parameters;
144  parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kDbSqlite3InMemory(), "false"));
145  _dbDriver = DBDriver::create(parameters);
146  if(!_dbDriver)
147  {
148  UERROR("Driver doesn't exist.");
149  return false;
150  }
151  if(!_dbDriver->openConnection(path))
152  {
153  UERROR("Can't open database %s", path.c_str());
154  delete _dbDriver;
155  _dbDriver = 0;
156  return false;
157  }
158 
160  _currentId = _ids.begin();
161  if(_startId>0 && _ids.size())
162  {
163  std::set<int>::iterator iter = _ids.find(_startId);
164  if(iter == _ids.end())
165  {
166  UWARN("Start index is too high (%d), the last ID in database is %d. Starting from beginning...", _startId, *_ids.rbegin());
167  }
168  else
169  {
170  _currentId = iter;
171  }
172  }
173 
174  if(_ids.size())
175  {
176  std::vector<CameraModel> models;
177  StereoCameraModel stereoModel;
178  if(_dbDriver->getCalibration(*_ids.begin(), models, stereoModel))
179  {
180  if(models.size())
181  {
182  if(models.at(0).isValidForProjection())
183  {
184  _calibrated = true;
185  }
186  else if(models.at(0).fx() && models.at(0).fy() && models.at(0).imageWidth() == 0)
187  {
188  // backward compatibility for databases not saving cx,cy and imageSize
189  SensorData data;
190  _dbDriver->getNodeData(*_ids.begin(), data, true, false, false, false);
191  cv::Mat rgb;
192  data.uncompressData(&rgb, 0); // this will update camera models if old format
193  if(data.cameraModels().size() && data.cameraModels().at(0).isValidForProjection())
194  {
195  _calibrated = true;
196  }
197  }
198  }
199  else if(stereoModel.isValidForProjection())
200  {
201  _calibrated = true;
202  }
203  }
204  }
205  else
206  {
207  _calibrated = true; // database is empty, make sure calibration warning is not shown.
208  }
209 
210  _timer.start();
211 
212  return true;
213 }
214 
216 {
217  return _calibrated;
218 }
219 
220 std::string DBReader::getSerial() const
221 {
222  return "DBReader";
223 }
224 
226 {
227  SensorData data = this->getNextData(info);
228  if(data.id()>0 && _stopId>0 && data.id() > _stopId)
229  {
230  UINFO("Last ID %d has been reached! Ignoring", _stopId);
231  return SensorData();
232  }
233  if(data.id() == 0)
234  {
235  UINFO("no more images...");
236  while(_paths.size() > 1 && data.id() == 0)
237  {
238  _paths.pop_front();
239  UWARN("Loading next database \"%s\"...", _paths.front().c_str());
240  if(!this->init())
241  {
242  UERROR("Failed to initialize the next database \"%s\"", _paths.front().c_str());
243  return data;
244  }
245  else
246  {
247  data = this->getNextData(info);
248  }
249  }
250  }
251 
252  if(data.id())
253  {
254  std::string goalId;
255  double previousStamp = data.stamp();
256  if(previousStamp == 0)
257  {
258  data.setStamp(UTimer::now());
259  }
260 
261  if(!_goalsIgnored &&
262  data.userDataRaw().type() == CV_8SC1 &&
263  data.userDataRaw().cols >= 7 && // including null str ending
264  data.userDataRaw().rows == 1 &&
265  memcmp(data.userDataRaw().data, "GOAL:", 5) == 0)
266  {
267  //GOAL format detected, remove it from the user data and send it as goal event
268  std::string goalStr = (const char *)data.userDataRaw().data;
269  if(!goalStr.empty())
270  {
271  std::list<std::string> strs = uSplit(goalStr, ':');
272  if(strs.size() == 2)
273  {
274  goalId = *strs.rbegin();
275  data.setUserData(cv::Mat());
276 
277  double delay = 0.0;
278  if(!_ignoreGoalDelay && _currentId != _ids.end())
279  {
280  // get stamp for the next signature to compute the delay
281  // that was used originally for planning
282  int weight;
283  std::string label;
284  double stamp;
285  int mapId;
286  Transform localTransform, pose, groundTruth;
287  std::vector<float> velocity;
288  GPS gps;
289  EnvSensors sensors;
290  _dbDriver->getNodeInfo(*_currentId, pose, mapId, weight, label, stamp, groundTruth, velocity, gps, sensors);
291  if(previousStamp && stamp && stamp > previousStamp)
292  {
293  delay = stamp - previousStamp;
294  }
295  }
296 
297  if(delay > 0.0)
298  {
299  UWARN("Goal \"%s\" detected, posting it! Waiting %f seconds before sending next data...",
300  goalId.c_str(), delay);
301  }
302  else
303  {
304  UWARN("Goal \"%s\" detected, posting it!", goalId.c_str());
305  }
306 
307  if(uIsInteger(goalId))
308  {
310  }
311  else
312  {
314  }
315 
316  if(delay > 0.0)
317  {
318  uSleep(delay*1000);
319  }
320  }
321  }
322  }
323  }
324  return data;
325 }
326 
328 {
329  SensorData data;
330  if(_dbDriver)
331  {
332  if(_currentId != _ids.end())
333  {
334  std::list<int> signIds;
335  signIds.push_back(*_currentId);
336  std::list<Signature *> signatures;
337  _dbDriver->loadSignatures(signIds, signatures);
338  if(signatures.empty())
339  {
340  return data;
341  }
342  _dbDriver->loadNodeData(signatures);
343  Signature * s = signatures.front();
344  data = s->sensorData();
345 
346  // info
347  Transform pose = s->getPose();
348  Transform globalPose;
349  cv::Mat globalPoseCov;
350 
351  std::multimap<int, Link> priorLinks;
353  if( priorLinks.size() &&
354  !priorLinks.begin()->second.transform().isNull() &&
355  priorLinks.begin()->second.infMatrix().cols == 6 &&
356  priorLinks.begin()->second.infMatrix().rows == 6)
357  {
358  globalPose = priorLinks.begin()->second.transform();
359  globalPoseCov = priorLinks.begin()->second.infMatrix().inv();
360  if(data.gps().stamp() != 0.0 &&
361  globalPoseCov.at<double>(3,3)>=9999 &&
362  globalPoseCov.at<double>(4,4)>=9999 &&
363  globalPoseCov.at<double>(5,5)>=9999)
364  {
365  // clear global pose as GPS was used for prior
366  globalPose.setNull();
367  }
368  }
369 
370  Transform gravityTransform;
371  std::multimap<int, Link> gravityLinks;
372  _dbDriver->loadLinks(*_currentId, gravityLinks, Link::kGravity);
373  if( gravityLinks.size() &&
374  !gravityLinks.begin()->second.transform().isNull() &&
375  gravityLinks.begin()->second.infMatrix().cols == 6 &&
376  gravityLinks.begin()->second.infMatrix().rows == 6)
377  {
378  gravityTransform = gravityLinks.begin()->second.transform();
379  }
380 
381  cv::Mat infMatrix = cv::Mat::eye(6,6,CV_64FC1);
382  if(!_odometryIgnored)
383  {
384  std::multimap<int, Link> links;
386  if(links.size() && links.begin()->first < *_currentId)
387  {
388  // assume the first is the backward neighbor, take its variance
389  infMatrix = links.begin()->second.infMatrix();
390  _previousInfMatrix = infMatrix;
391  }
392  else if(_previousMapId != s->mapId())
393  {
394  // first node, set high variance to make rtabmap trigger a new map
395  infMatrix /= 9999.0;
396  UDEBUG("First node of map %d, variance set to 9999", s->mapId());
397  }
398  else
399  {
400  if(_previousInfMatrix.empty())
401  {
402  _previousInfMatrix = cv::Mat::eye(6,6,CV_64FC1);
403  }
404  // we have a node not linked to map, use last variance
405  infMatrix = _previousInfMatrix;
406  }
407  _previousMapId = s->mapId();
408  }
409  else
410  {
411  pose.setNull();
412  }
413 
414  int seq = *_currentId;
415  ++_currentId;
416 
417  // Frame rate
418  if(this->getImageRate() < 0.0f)
419  {
420  if(s->getStamp() == 0)
421  {
422  UERROR("The option to use database stamps is set (framerate<0), but there are no stamps saved in the database! Aborting...");
423  delete s;
424  return data;
425  }
426  else if(_previousMapID == s->mapId() && _previousStamp > 0)
427  {
428  float ratio = -this->getImageRate();
429  int sleepTime = 1000.0*(s->getStamp()-_previousStamp)/ratio - 1000.0*_timer.getElapsedTime();
430  if(sleepTime > 10000)
431  {
432  UWARN("Detected long delay (%d sec, stamps = %f vs %f). Waiting a maximum of 10 seconds.",
433  sleepTime/1000, _previousStamp, s->getStamp());
434  sleepTime = 10000;
435  }
436  if(sleepTime > 2)
437  {
438  uSleep(sleepTime-2);
439  }
440 
441  // Add precision at the cost of a small overhead
442  while(_timer.getElapsedTime() < (s->getStamp()-_previousStamp)/ratio-0.000001)
443  {
444  //
445  }
446 
447  double slept = _timer.getElapsedTime();
448  _timer.start();
449  UDEBUG("slept=%fs vs target=%fs (ratio=%f)", slept, (s->getStamp()-_previousStamp)/ratio, ratio);
450  }
451  _previousStamp = s->getStamp();
452  _previousMapID = s->mapId();
453  }
454 
455  data.uncompressData();
456  if(data.cameraModels().size() > 1 &&
457  _cameraIndex >= 0)
458  {
459  if(_cameraIndex < (int)data.cameraModels().size())
460  {
461  // select one camera
462  int subImageWidth = data.imageRaw().cols/data.cameraModels().size();
463  cv::Mat image;
464  UASSERT(!data.imageRaw().empty() &&
465  data.imageRaw().cols % data.cameraModels().size() == 0 &&
466  _cameraIndex*subImageWidth < data.imageRaw().cols);
467  image= cv::Mat(data.imageRaw(),
468  cv::Rect(_cameraIndex*subImageWidth, 0, subImageWidth, data.imageRaw().rows)).clone();
469 
470  cv::Mat depth;
471  if(!data.depthOrRightRaw().empty())
472  {
473  UASSERT(data.depthOrRightRaw().cols % data.cameraModels().size() == 0 &&
474  subImageWidth == data.depthOrRightRaw().cols/(int)data.cameraModels().size() &&
475  _cameraIndex*subImageWidth < data.depthOrRightRaw().cols);
476  depth = cv::Mat(data.depthOrRightRaw(),
477  cv::Rect(_cameraIndex*subImageWidth, 0, subImageWidth, data.depthOrRightRaw().rows)).clone();
478  }
479  data.setRGBDImage(image, depth, data.cameraModels().at(_cameraIndex));
480  }
481  else
482  {
483  UWARN("DBReader: Camera index %d doesn't exist! Camera models = %d.", _cameraIndex, (int)data.cameraModels().size());
484  }
485  }
486  data.setId(seq);
487  data.setStamp(s->getStamp());
489  if(globalPose.isNull())
490  {
491  data.setGlobalPose(globalPose, globalPoseCov);
492  }
493  if(!gravityTransform.isNull())
494  {
495  Eigen::Quaterniond q = gravityTransform.getQuaterniond();
496  data.setIMU(IMU(
497  cv::Vec4d(q.x(), q.y(), q.z(), q.w()), cv::Mat::eye(3,3,CV_64FC1),
498  cv::Vec3d(), cv::Mat(),
499  cv::Vec3d(), cv::Mat(),
500  Transform::getIdentity())); // we assume that gravity links are already transformed in base_link
501  }
502 
503  UDEBUG("Laser=%d RGB/Left=%d Depth/Right=%d, Grid=%d, UserData=%d, GlobalPose=%d, GPS=%d, IMU=%d",
504  data.laserScanRaw().isEmpty()?0:1,
505  data.imageRaw().empty()?0:1,
506  data.depthOrRightRaw().empty()?0:1,
507  data.gridCellSize()==0.0f?0:1,
508  data.userDataRaw().empty()?0:1,
509  globalPose.isNull()?0:1,
510  data.gps().stamp()!=0.0?1:0,
511  gravityTransform.isNull()?0:1);
512 
513  cv::Mat descriptors = s->getWordsDescriptors().clone();
514  const std::vector<cv::KeyPoint> & keypoints = s->getWordsKpts();
515  const std::vector<cv::Point3f> & keypoints3D = s->getWords3();
516  if(!keypoints.empty() &&
517  (keypoints3D.empty() || keypoints.size() == keypoints3D.size()) &&
518  (descriptors.empty() || (int)keypoints.size() == descriptors.rows))
519  {
520  data.setFeatures(keypoints, keypoints3D, descriptors);
521  }
522  else if(!keypoints.empty() && (!keypoints3D.empty() || !descriptors.empty()))
523  {
524  UERROR("Missing feature data, features won't be published.");
525  }
526 
527  if(data.imageCompressed().empty() && s->getWeight()>=0 && keypoints.empty())
528  {
529  UWARN("No image loaded from the database for id=%d!", seq);
530  }
531 
532  if(!_odometryIgnored)
533  {
534  if(pose.isNull())
535  {
536  UWARN("Reading the database: odometry is null! "
537  "Please set \"Ignore odometry = true\" if there is "
538  "no odometry in the database.");
539  }
540  if(info)
541  {
542  info->odomPose = pose;
543  info->odomCovariance = infMatrix.inv();
544  info->odomVelocity = s->getVelocity();
545  UDEBUG("odom variance = %f/%f", info->odomCovariance.at<double>(0,0), info->odomCovariance.at<double>(5,5));
546  }
547  }
548  delete s;
549  }
550  }
551  else
552  {
553  UERROR("Not initialized...");
554  }
555  return data;
556 }
557 
558 } /* namespace rtabmap */
bool uIsInteger(const std::string &str, bool checkForSign=true)
Definition: UStl.h:632
cv::Mat odomCovariance
Definition: CameraInfo.h:70
std::list< std::string > _paths
Definition: DBReader.h:81
cv::Mat _previousInfMatrix
Definition: DBReader.h:94
static void post(UEvent *event, bool async=true, const UEventsSender *sender=0)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
Definition: DBReader.cpp:112
const Transform & getGroundTruthPose() const
Definition: Signature.h:134
int mapId() const
Definition: Signature.h:71
SensorData getNextData(CameraInfo *info=0)
Definition: DBReader.cpp:327
f
const std::vector< float > & getVelocity() const
Definition: Signature.h:135
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const
Definition: DBDriver.cpp:876
void setGlobalPose(const Transform &pose, const cv::Mat &covariance)
Definition: SensorData.h:261
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
static Transform getIdentity()
Definition: Transform.cpp:380
DBReader(const std::string &databasePath, float frameRate=0.0f, bool odometryIgnored=false, bool ignoreGoalDelay=false, bool goalsIgnored=false, int startId=0, int cameraIndex=-1, int stopId=0)
Definition: DBReader.cpp:45
bool _goalsIgnored
Definition: DBReader.h:84
bool isEmpty() const
Definition: LaserScan.h:101
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:193
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:675
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
double _previousStamp
Definition: DBReader.h:95
float gridCellSize() const
Definition: SensorData.h:245
void setId(int id)
Definition: SensorData.h:156
std::vector< float > odomVelocity
Definition: CameraInfo.h:71
Some conversion functions.
const LaserScan & laserScanRaw() const
Definition: SensorData.h:166
void loadLinks(int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const
Definition: DBDriver.cpp:815
const cv::Mat & imageRaw() const
Definition: SensorData.h:164
virtual ~DBReader()
Definition: DBReader.cpp:103
double getElapsedTime()
Definition: UTimer.cpp:97
const std::vector< cv::KeyPoint > & getWordsKpts() const
Definition: Signature.h:112
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
Definition: UStl.h:566
double getStamp() const
Definition: Signature.h:79
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
#define UASSERT(condition)
Wrappers of STL for convenient functions.
bool isNull() const
Definition: Transform.cpp:107
bool _ignoreGoalDelay
Definition: DBReader.h:83
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
void loadNodeData(Signature *signature, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:648
void loadSignatures(const std::list< int > &ids, std::list< Signature * > &signatures, std::set< int > *loadedFromTrash=0)
Definition: DBDriver.cpp:554
DBDriver * _dbDriver
Definition: DBReader.h:89
std::set< int > _ids
Definition: DBReader.h:91
bool getCalibration(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const
Definition: DBDriver.cpp:726
const cv::Mat & getWordsDescriptors() const
Definition: Signature.h:115
const GPS & gps() const
Definition: SensorData.h:266
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:165
void start()
Definition: UTimer.cpp:87
const cv::Mat & userDataRaw() const
Definition: SensorData.h:227
int id() const
Definition: SensorData.h:155
int getWeight() const
Definition: Signature.h:74
double stamp() const
Definition: SensorData.h:157
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
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
Definition: DBDriver.cpp:776
void setUserData(const cv::Mat &userData, bool clearPreviousData=true)
Definition: SensorData.cpp:378
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
float getImageRate() const
Definition: Camera.h:63
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:215
const Transform & getPose() const
Definition: Signature.h:132
const std::vector< cv::Point3f > & getWords3() const
Definition: Signature.h:131
#define UDEBUG(...)
SensorData & sensorData()
Definition: Signature.h:137
bool exists()
Definition: UFile.h:104
virtual bool isCalibrated() const
Definition: DBReader.cpp:215
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
static double now()
Definition: UTimer.cpp:80
void setStamp(double stamp)
Definition: SensorData.h:158
const cv::Mat & imageCompressed() const
Definition: SensorData.h:160
Eigen::Quaterniond getQuaterniond() const
Definition: Transform.cpp:375
void setIMU(const IMU &imu)
Definition: SensorData.h:268
std::set< int >::iterator _currentId
Definition: DBReader.h:92
void setGroundTruth(const Transform &pose)
Definition: SensorData.h:258
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
bool _odometryIgnored
Definition: DBReader.h:82
Transform odomPose
Definition: CameraInfo.h:69
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
Definition: SensorData.cpp:757
virtual SensorData captureImage(CameraInfo *info=0)
Definition: DBReader.cpp:225
virtual std::string getSerial() const
Definition: DBReader.cpp:220
#define UINFO(...)
const double & stamp() const
Definition: GPS.h:59


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58