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  bool intermediateNodesIgnored,
54  bool landmarksIgnored,
55  bool featuresIgnored,
56  int startMapId,
57  int stopMapId) :
58  Camera(frameRate),
59  _paths(uSplit(databasePath, ';')),
60  _odometryIgnored(odometryIgnored),
61  _ignoreGoalDelay(ignoreGoalDelay),
62  _goalsIgnored(goalsIgnored),
63  _startId(startId),
64  _stopId(stopId),
65  _cameraIndex(cameraIndex),
66  _intermediateNodesIgnored(intermediateNodesIgnored),
67  _landmarksIgnored(landmarksIgnored),
68  _featuresIgnored(featuresIgnored),
69  _startMapId(startMapId),
70  _stopMapId(stopMapId),
71  _dbDriver(0),
72  _currentId(_ids.end()),
73  _previousMapId(-1),
74  _previousStamp(0),
75  _previousMapID(0),
76  _calibrated(false)
77 {
78  if(_stopId>0 && _stopId<_startId)
79  {
80  _stopId = _startId;
81  }
82 
84  {
86  }
87 }
88 
89 DBReader::DBReader(const std::list<std::string> & databasePaths,
90  float frameRate,
91  bool odometryIgnored,
92  bool ignoreGoalDelay,
93  bool goalsIgnored,
94  int startId,
95  int cameraIndex,
96  int stopId,
97  bool intermediateNodesIgnored,
98  bool landmarksIgnored,
99  bool featuresIgnored,
100  int startMapId,
101  int stopMapId) :
102  Camera(frameRate),
103  _paths(databasePaths),
104  _odometryIgnored(odometryIgnored),
105  _ignoreGoalDelay(ignoreGoalDelay),
106  _goalsIgnored(goalsIgnored),
107  _startId(startId),
108  _stopId(stopId),
109  _cameraIndex(cameraIndex),
110  _intermediateNodesIgnored(intermediateNodesIgnored),
111  _landmarksIgnored(landmarksIgnored),
112  _featuresIgnored(featuresIgnored),
113  _startMapId(startMapId),
114  _stopMapId(stopMapId),
115  _dbDriver(0),
116  _currentId(_ids.end()),
117  _previousMapId(-1),
118  _previousStamp(0),
119  _previousMapID(0),
121 {
122  if(_stopId>0 && _stopId<_startId)
123  {
124  _stopId = _startId;
125  }
126 
128  {
130  }
131 }
132 
134 {
135  if(_dbDriver)
136  {
138  delete _dbDriver;
139  }
140 }
141 
143  const std::string & calibrationFolder,
144  const std::string & cameraName)
145 {
146  if(_dbDriver)
147  {
149  delete _dbDriver;
150  _dbDriver = 0;
151  }
152  _ids.clear();
153  _currentId=_ids.end();
154  _previousMapId = -1;
155  _previousInfMatrix = cv::Mat();
156  _previousStamp = 0;
157  _previousMapID = 0;
158  _calibrated = false;
159 
160  if(_paths.size() == 0)
161  {
162  UERROR("No database path set...");
163  return false;
164  }
165 
166  std::string path = _paths.front();
167  if(!UFile::exists(path))
168  {
169  UERROR("Database path does not exist (%s)", path.c_str());
170  return false;
171  }
172 
173  rtabmap::ParametersMap parameters;
174  parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kDbSqlite3InMemory(), "false"));
175  _dbDriver = DBDriver::create(parameters);
176  if(!_dbDriver)
177  {
178  UERROR("Driver doesn't exist.");
179  return false;
180  }
181  if(!_dbDriver->openConnection(path))
182  {
183  UERROR("Can't open database %s", path.c_str());
184  delete _dbDriver;
185  _dbDriver = 0;
186  return false;
187  }
188 
190  _currentId = _ids.begin();
191  if(_startId>0 && _ids.size())
192  {
193  std::set<int>::iterator iter = _ids.find(_startId);
194  if(iter == _ids.end())
195  {
196  UWARN("Start index is too high (%d), the last ID in database is %d. Starting from beginning...", _startId, *_ids.rbegin());
197  }
198  else
199  {
200  _currentId = iter;
201  }
202  }
203 
204  if(_ids.size())
205  {
206  std::vector<CameraModel> models;
207  std::vector<StereoCameraModel> stereoModels;
208  if(_dbDriver->getCalibration(*_ids.begin(), models, stereoModels))
209  {
210  if(models.size())
211  {
212  if(models.at(0).isValidForProjection())
213  {
214  _calibrated = true;
215  }
216  else if(models.at(0).fx() && models.at(0).fy() && models.at(0).imageWidth() == 0)
217  {
218  // backward compatibility for databases not saving cx,cy and imageSize
220  _dbDriver->getNodeData(*_ids.begin(), data, true, false, false, false);
221  cv::Mat rgb;
222  data.uncompressData(&rgb, 0); // this will update camera models if old format
223  if(data.cameraModels().size() && data.cameraModels().at(0).isValidForProjection())
224  {
225  _calibrated = true;
226  }
227  }
228  }
229  else if(stereoModels.size() && stereoModels.at(0).isValidForProjection())
230  {
231  _calibrated = true;
232  }
233  else
234  {
235  Signature * s = _dbDriver->loadSignature(*_ids.begin());
237  if( s->sensorData().imageCompressed().empty() &&
238  s->getWords().empty() &&
240  {
241  _calibrated = true; // only scans
242  }
243  delete s;
244  }
245  }
246  }
247  else
248  {
249  _calibrated = true; // database is empty, make sure calibration warning is not shown.
250  }
251 
252  _timer.start();
253 
254  return true;
255 }
256 
258 {
259  return _calibrated;
260 }
261 
262 std::string DBReader::getSerial() const
263 {
264  return "DBReader";
265 }
266 
268 {
269  SensorData data = this->getNextData(info);
270  if(data.id()>0 && _stopId>0 && data.id() > _stopId)
271  {
272  UINFO("Last ID %d has been reached! Ignoring", _stopId);
273  return SensorData();
274  }
275  if(data.id() == 0)
276  {
277  UINFO("no more images...");
278  while(_paths.size() > 1 && data.id() == 0)
279  {
280  _paths.pop_front();
281  UWARN("Loading next database \"%s\"...", _paths.front().c_str());
282  if(!this->init())
283  {
284  UERROR("Failed to initialize the next database \"%s\"", _paths.front().c_str());
285  return data;
286  }
287  else
288  {
289  data = this->getNextData(info);
290  }
291  }
292  }
293 
294  if(data.id())
295  {
296  std::string goalId;
297  double previousStamp = data.stamp();
298  if(previousStamp == 0)
299  {
300  data.setStamp(UTimer::now());
301  }
302 
303  if(!_goalsIgnored &&
304  data.userDataRaw().type() == CV_8SC1 &&
305  data.userDataRaw().cols >= 7 && // including null str ending
306  data.userDataRaw().rows == 1 &&
307  memcmp(data.userDataRaw().data, "GOAL:", 5) == 0)
308  {
309  //GOAL format detected, remove it from the user data and send it as goal event
310  std::string goalStr = (const char *)data.userDataRaw().data;
311  if(!goalStr.empty())
312  {
313  std::list<std::string> strs = uSplit(goalStr, ':');
314  if(strs.size() == 2)
315  {
316  goalId = *strs.rbegin();
317  data.setUserData(cv::Mat());
318 
319  double delay = 0.0;
320  if(!_ignoreGoalDelay && _currentId != _ids.end())
321  {
322  // get stamp for the next signature to compute the delay
323  // that was used originally for planning
324  int weight;
325  std::string label;
326  double stamp;
327  int mapId;
328  Transform localTransform, pose, groundTruth;
329  std::vector<float> velocity;
330  GPS gps;
331  EnvSensors sensors;
332  _dbDriver->getNodeInfo(*_currentId, pose, mapId, weight, label, stamp, groundTruth, velocity, gps, sensors);
333  if(previousStamp && stamp && stamp > previousStamp)
334  {
335  delay = stamp - previousStamp;
336  }
337  }
338 
339  if(delay > 0.0)
340  {
341  UWARN("Goal \"%s\" detected, posting it! Waiting %f seconds before sending next data...",
342  goalId.c_str(), delay);
343  }
344  else
345  {
346  UWARN("Goal \"%s\" detected, posting it!", goalId.c_str());
347  }
348 
349  if(uIsInteger(goalId))
350  {
352  }
353  else
354  {
356  }
357 
358  if(delay > 0.0)
359  {
360  uSleep(delay*1000);
361  }
362  }
363  }
364  }
365  }
366  return data;
367 }
368 
370 {
372  if(_dbDriver)
373  {
374  while(_currentId != _ids.end())
375  {
376  std::list<int> signIds;
377  signIds.push_back(*_currentId);
378  std::list<Signature *> signatures;
379  _dbDriver->loadSignatures(signIds, signatures);
380  if(signatures.empty())
381  {
382  return data;
383  }
384  _dbDriver->loadNodeData(signatures);
385  Signature * s = signatures.front();
386 
387  if(_intermediateNodesIgnored && s->getWeight() == -1)
388  {
389  UDEBUG("Ignoring node %d (intermediate nodes ignored)", s->id());
390  ++_currentId;
391  delete s;
392  continue;
393  }
394 
395  if(s->mapId() < _startMapId || (_stopMapId>=0 && s->mapId() > _stopMapId))
396  {
397  UDEBUG("Ignoring node %d (map id=%d, min=%d max=%d)", s->id(), s->mapId(), _startMapId, _stopMapId);
398  ++_currentId;
399  delete s;
400  continue;
401  }
402 
403  data = s->sensorData();
404 
405  // info
406  Transform pose = s->getPose();
407  Transform globalPose;
408  cv::Mat globalPoseCov;
409 
410  std::multimap<int, Link> priorLinks;
412  if( priorLinks.size() &&
413  !priorLinks.begin()->second.transform().isNull() &&
414  priorLinks.begin()->second.infMatrix().cols == 6 &&
415  priorLinks.begin()->second.infMatrix().rows == 6)
416  {
417  globalPose = priorLinks.begin()->second.transform();
418  globalPoseCov = priorLinks.begin()->second.infMatrix().inv();
419  if(data.gps().stamp() != 0.0 &&
420  globalPoseCov.at<double>(3,3)>=9999 &&
421  globalPoseCov.at<double>(4,4)>=9999 &&
422  globalPoseCov.at<double>(5,5)>=9999)
423  {
424  // clear global pose as GPS was used for prior
425  globalPose.setNull();
426  }
427  }
428 
429  Transform gravityTransform;
430  std::multimap<int, Link> gravityLinks;
431  _dbDriver->loadLinks(*_currentId, gravityLinks, Link::kGravity);
432  if( gravityLinks.size() &&
433  !gravityLinks.begin()->second.transform().isNull() &&
434  gravityLinks.begin()->second.infMatrix().cols == 6 &&
435  gravityLinks.begin()->second.infMatrix().rows == 6)
436  {
437  gravityTransform = gravityLinks.begin()->second.transform();
438  }
439 
440  Landmarks landmarks;
441  if(!_landmarksIgnored)
442  {
443  std::multimap<int, Link> landmarkLinks;
444  _dbDriver->loadLinks(*_currentId, landmarkLinks, Link::kLandmark);
445  for(std::multimap<int, Link>::iterator iter=landmarkLinks.begin(); iter!=landmarkLinks.end(); ++iter)
446  {
447  cv::Mat landmarkSize = iter->second.uncompressUserDataConst();
448  landmarks.insert(std::make_pair(-iter->first,
449  Landmark(-iter->first,
450  !landmarkSize.empty() && landmarkSize.type() == CV_32FC1 && landmarkSize.total()==1?landmarkSize.at<float>(0,0):0.0f,
451  iter->second.transform(),
452  iter->second.infMatrix().inv())));
453  }
454  }
455 
456  cv::Mat infMatrix = cv::Mat::eye(6,6,CV_64FC1);
457  if(!_odometryIgnored)
458  {
459  std::multimap<int, Link> links;
461  if(links.size() && links.begin()->first < *_currentId)
462  {
463  // assume the first is the backward neighbor, take its variance
464  infMatrix = links.begin()->second.infMatrix();
465  _previousInfMatrix = infMatrix;
466  }
467  else
468  {
469  if(_previousMapId != s->mapId())
470  {
471  // first node, set high variance to make rtabmap trigger a new map
472  infMatrix /= 9999.0;
473  UDEBUG("First node of map %d, variance set to 9999", s->mapId());
474  }
475  else
476  {
477  // if localization data saved in database, covariance will be set in a prior link
479  if(links.size())
480  {
481  // assume the first is the backward neighbor, take its variance
482  infMatrix = links.begin()->second.infMatrix();
483  _previousInfMatrix = infMatrix;
484  }
485  else
486  {
487  if(_previousInfMatrix.empty())
488  {
489  _previousInfMatrix = cv::Mat::eye(6,6,CV_64FC1);
490  }
491  // we have a node not linked to map, use last variance
492  infMatrix = _previousInfMatrix;
493  }
494  }
495  }
496  _previousMapId = s->mapId();
497  }
498  else
499  {
500  pose.setNull();
501  }
502 
503  int seq = *_currentId;
504  ++_currentId;
505 
506  // Frame rate
507  if(this->getImageRate() < 0.0f)
508  {
509  if(s->getStamp() == 0)
510  {
511  UERROR("The option to use database stamps is set (framerate<0), but there are no stamps saved in the database! Aborting...");
512  delete s;
513  return data;
514  }
515  else if(_previousMapID == s->mapId() && _previousStamp > 0)
516  {
517  float ratio = -this->getImageRate();
518  int sleepTime = 1000.0*(s->getStamp()-_previousStamp)/ratio - 1000.0*_timer.getElapsedTime();
519  if(sleepTime > 10000)
520  {
521  UWARN("Detected long delay (%d sec, stamps = %f vs %f). Waiting a maximum of 10 seconds.",
522  sleepTime/1000, _previousStamp, s->getStamp());
523  sleepTime = 10000;
524  }
525  if(sleepTime > 2)
526  {
527  uSleep(sleepTime-2);
528  }
529 
530  // Add precision at the cost of a small overhead
531  while(_timer.getElapsedTime() < (s->getStamp()-_previousStamp)/ratio-0.000001)
532  {
533  //
534  }
535 
536  double slept = _timer.getElapsedTime();
537  _timer.start();
538  UDEBUG("slept=%fs vs target=%fs (ratio=%f)", slept, (s->getStamp()-_previousStamp)/ratio, ratio);
539  }
540  _previousStamp = s->getStamp();
541  _previousMapID = s->mapId();
542  }
543 
544  data.uncompressData();
545  if(data.cameraModels().size() > 1 &&
546  _cameraIndex >= 0)
547  {
548  if(_cameraIndex < (int)data.cameraModels().size())
549  {
550  // select one camera
551  int subImageWidth = data.imageRaw().cols/data.cameraModels().size();
552  cv::Mat image;
553  UASSERT(!data.imageRaw().empty() &&
554  data.imageRaw().cols % data.cameraModels().size() == 0 &&
555  _cameraIndex*subImageWidth < data.imageRaw().cols);
556  image= cv::Mat(data.imageRaw(),
557  cv::Rect(_cameraIndex*subImageWidth, 0, subImageWidth, data.imageRaw().rows)).clone();
558 
559  cv::Mat depth;
560  if(!data.depthOrRightRaw().empty())
561  {
562  UASSERT(data.depthOrRightRaw().cols % data.cameraModels().size() == 0 &&
563  subImageWidth == data.depthOrRightRaw().cols/(int)data.cameraModels().size() &&
564  _cameraIndex*subImageWidth < data.depthOrRightRaw().cols);
565  depth = cv::Mat(data.depthOrRightRaw(),
566  cv::Rect(_cameraIndex*subImageWidth, 0, subImageWidth, data.depthOrRightRaw().rows)).clone();
567  }
568  data.setRGBDImage(image, depth, data.cameraModels().at(_cameraIndex));
569  }
570  else
571  {
572  UWARN("DBReader: Camera index %d doesn't exist! Camera models = %d.", _cameraIndex, (int)data.cameraModels().size());
573  }
574  }
575  data.setId(seq);
576  data.setStamp(s->getStamp());
578  if(!globalPose.isNull())
579  {
580  data.setGlobalPose(globalPose, globalPoseCov);
581  }
582  if(!gravityTransform.isNull())
583  {
584  Eigen::Quaterniond q = gravityTransform.getQuaterniond();
585  data.setIMU(IMU(
586  cv::Vec4d(q.x(), q.y(), q.z(), q.w()), cv::Mat::eye(3,3,CV_64FC1),
587  cv::Vec3d(), cv::Mat(),
588  cv::Vec3d(), cv::Mat(),
589  Transform::getIdentity())); // we assume that gravity links are already transformed in base_link
590  }
591  data.setLandmarks(landmarks);
592 
593  UDEBUG("Laser=%d RGB/Left=%d Depth/Right=%d, Grid=%d, UserData=%d, GlobalPose=%d, GPS=%d, IMU=%d",
594  data.laserScanRaw().isEmpty()?0:1,
595  data.imageRaw().empty()?0:1,
596  data.depthOrRightRaw().empty()?0:1,
597  data.gridCellSize()==0.0f?0:1,
598  data.userDataRaw().empty()?0:1,
599  globalPose.isNull()?0:1,
600  data.gps().stamp()!=0.0?1:0,
601  gravityTransform.isNull()?0:1);
602 
603  cv::Mat descriptors = s->getWordsDescriptors().clone();
604  const std::vector<cv::KeyPoint> & keypoints = s->getWordsKpts();
605  const std::vector<cv::Point3f> & keypoints3D = s->getWords3();
606  if(!_featuresIgnored &&
607  !keypoints.empty() &&
608  (keypoints3D.empty() || keypoints.size() == keypoints3D.size()) &&
609  (descriptors.empty() || (int)keypoints.size() == descriptors.rows))
610  {
611  data.setFeatures(keypoints, keypoints3D, descriptors);
612  }
613  else if(!_featuresIgnored && !keypoints.empty() && (!keypoints3D.empty() || !descriptors.empty()))
614  {
615  UERROR("Missing feature data, features won't be published.");
616  }
617 
618  if(data.imageCompressed().empty() && s->getWeight()>=0 && keypoints.empty())
619  {
620  UWARN("No image loaded from the database for id=%d!", seq);
621  }
622 
623  if(!_odometryIgnored)
624  {
625  if(pose.isNull())
626  {
627  UWARN("Reading the database: odometry is null! "
628  "Please set \"Ignore odometry = true\" if there is "
629  "no odometry in the database.");
630  }
631  if(info)
632  {
633  info->odomPose = pose;
634  info->odomCovariance = infMatrix.inv();
635  info->odomVelocity = s->getVelocity();
636  UDEBUG("odom variance = %f/%f", info->odomCovariance.at<double>(0,0), info->odomCovariance.at<double>(5,5));
637  }
638  }
639  delete s;
640  break;
641  }
642  }
643  else
644  {
645  UERROR("Not initialized...");
646  }
647  return data;
648 }
649 
650 } /* 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:93
cv::Mat _previousInfMatrix
Definition: DBReader.h:111
const double & stamp() const
Definition: GPS.h:59
static void post(UEvent *event, bool async=true, const UEventsSender *sender=0)
const Transform & getGroundTruthPose() const
Definition: Signature.h:134
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
Definition: DBReader.cpp:142
Signature * loadSignature(int id, bool *loadedFromTrash=0)
Definition: DBDriver.cpp:537
const std::vector< float > & getVelocity() const
Definition: Signature.h:135
SensorData getNextData(CameraInfo *info=0)
Definition: DBReader.cpp:369
f
const LaserScan & laserScanCompressed() const
Definition: SensorData.h:181
bool _landmarksIgnored
Definition: DBReader.h:101
virtual bool isCalibrated() const
Definition: DBReader.cpp:257
void setGlobalPose(const Transform &pose, const cv::Mat &covariance)
Definition: SensorData.h:282
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
static Transform getIdentity()
Definition: Transform.cpp:401
const cv::Mat & getWordsDescriptors() const
Definition: Signature.h:115
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
data
bool _goalsIgnored
Definition: DBReader.h:96
std::map< int, Landmark > Landmarks
Definition: Landmark.h:78
int mapId() const
Definition: Signature.h:71
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:227
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
double _previousStamp
Definition: DBReader.h:112
const std::vector< cv::Point3f > & getWords3() const
Definition: Signature.h:131
virtual std::string getSerial() const
Definition: DBReader.cpp:262
void setId(int id)
Definition: SensorData.h:175
std::vector< float > odomVelocity
Definition: CameraInfo.h:71
Some conversion functions.
int getWeight() const
Definition: Signature.h:74
void loadLinks(int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const
Definition: DBDriver.cpp:815
bool isEmpty() const
Definition: LaserScan.h:125
virtual ~DBReader()
Definition: DBReader.cpp:133
double getElapsedTime()
Definition: UTimer.cpp:97
float gridCellSize() const
Definition: SensorData.h:266
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
const std::vector< cv::KeyPoint > & getWordsKpts() const
Definition: Signature.h:112
#define UASSERT(condition)
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, bool intermediateNodesIgnored=false, bool landmarksIgnored=false, bool featuresIgnored=false, int startMapId=0, int stopMapId=-1)
Definition: DBReader.cpp:45
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:566
int id() const
Definition: SensorData.h:174
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:236
const GPS & gps() const
Definition: SensorData.h:287
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
bool _ignoreGoalDelay
Definition: DBReader.h:95
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
DBDriver * _dbDriver
Definition: DBReader.h:106
bool getCalibration(int signatureId, std::vector< CameraModel > &models, std::vector< StereoCameraModel > &stereoModels) const
Definition: DBDriver.cpp:726
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false, bool ignoreIntermediateNodes=false) const
Definition: DBDriver.cpp:876
bool _intermediateNodesIgnored
Definition: DBReader.h:100
std::set< int > _ids
Definition: DBReader.h:108
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:675
bool empty() const
Definition: LaserScan.h:124
void start()
Definition: UTimer.cpp:87
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
float getImageRate() const
Definition: Camera.h:64
void setUserData(const cv::Mat &userData, bool clearPreviousData=true)
Definition: SensorData.cpp:422
bool isNull() const
Definition: Transform.cpp:107
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
const cv::Mat & userDataRaw() const
Definition: SensorData.h:248
#define UDEBUG(...)
SensorData & sensorData()
Definition: Signature.h:137
void loadNodeData(Signature *signature, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:648
bool exists()
Definition: UFile.h:104
void loadSignatures(const std::list< int > &ids, std::list< Signature *> &signatures, std::set< int > *loadedFromTrash=0)
Definition: DBDriver.cpp:554
#define UERROR(...)
const Transform & getPose() const
Definition: Signature.h:132
ULogger class and convenient macros.
#define UWARN(...)
bool _featuresIgnored
Definition: DBReader.h:102
int id() const
Definition: Signature.h:70
double stamp() const
Definition: SensorData.h:176
static double now()
Definition: UTimer.cpp:80
double getStamp() const
Definition: Signature.h:79
void setStamp(double stamp)
Definition: SensorData.h:177
void setLandmarks(const Landmarks &landmarks)
Definition: SensorData.h:296
void setIMU(const IMU &imu)
Definition: SensorData.h:289
std::set< int >::iterator _currentId
Definition: DBReader.h:109
void setGroundTruth(const Transform &pose)
Definition: SensorData.h:279
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
bool _odometryIgnored
Definition: DBReader.h:94
Transform odomPose
Definition: CameraInfo.h:69
Eigen::Quaterniond getQuaterniond() const
Definition: Transform.cpp:396
const cv::Mat & imageCompressed() const
Definition: SensorData.h:179
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
Definition: SensorData.cpp:801
end
virtual SensorData captureImage(CameraInfo *info=0)
Definition: DBReader.cpp:267
q
const std::multimap< int, int > & getWords() const
Definition: Signature.h:111
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28