DBReader.h
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 #ifndef DBREADER_H_
29 #define DBREADER_H_
30 
31 #include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
32 
33 #include <rtabmap/utilite/UTimer.h>
34 #include <rtabmap/core/Transform.h>
35 #include <rtabmap/core/Camera.h>
36 
37 #include <opencv2/core/core.hpp>
38 
39 #include <set>
40 #include <list>
41 
42 namespace rtabmap {
43 
44 class DBDriver;
45 
46 class RTABMAP_CORE_EXPORT DBReader : public Camera {
47 public:
48  DBReader(const std::string & databasePath,
49  float frameRate = 0.0f, // -1 = use Database stamps, 0 = inf
50  bool odometryIgnored = false,
51  bool ignoreGoalDelay = false,
52  bool goalsIgnored = false,
53  int startId = 0,
54  int cameraIndex = -1,
55  int stopId = 0,
56  bool intermediateNodesIgnored = false,
57  bool landmarksIgnored = false,
58  bool featuresIgnored = false,
59  int startMapId = 0,
60  int stopMapId = -1,
61  bool priorsIgnored = false);
62  DBReader(const std::list<std::string> & databasePaths,
63  float frameRate = 0.0f, // -1 = use Database stamps, 0 = inf
64  bool odometryIgnored = false,
65  bool ignoreGoalDelay = false,
66  bool goalsIgnored = false,
67  int startId = 0,
68  int cameraIndex = -1,
69  int stopId = 0,
70  bool intermediateNodesIgnored = false,
71  bool landmarksIgnored = false,
72  bool featuresIgnored = false,
73  int startMapId = 0,
74  int stopMapId = -1,
75  bool priorsIgnored = false);
76  virtual ~DBReader();
77 
78  virtual bool init(
79  const std::string & calibrationFolder = ".",
80  const std::string & cameraName = "");
81 
82  virtual bool isCalibrated() const;
83  virtual std::string getSerial() const;
84  virtual bool odomProvided() const {return !_odometryIgnored;}
85  virtual bool getPose(double stamp, Transform & pose, cv::Mat & covariance, double maxWaitTime = 0.06);
86 
87  const DBDriver * driver() const {return _dbDriver;}
88 
89 protected:
90  virtual SensorData captureImage(SensorCaptureInfo * info = 0);
91 
92 private:
93  SensorData getNextData(SensorCaptureInfo * info = 0);
94 
95 private:
96  std::list<std::string> _paths;
100  int _startId;
101  int _stopId;
109 
112  std::set<int> _ids;
113  std::set<int>::iterator _currentId;
119 };
120 
121 } /* namespace rtabmap */
122 #endif /* DBREADER_H_ */
rtabmap::SensorData
Definition: SensorData.h:51
rtabmap::DBReader::_calibrated
bool _calibrated
Definition: DBReader.h:118
rtabmap::DBReader::_landmarksIgnored
bool _landmarksIgnored
Definition: DBReader.h:104
rtabmap::DBReader::_previousMapID
int _previousMapID
Definition: DBReader.h:117
rtabmap::DBReader::_goalsIgnored
bool _goalsIgnored
Definition: DBReader.h:99
rtabmap::DBReader::_previousInfMatrix
cv::Mat _previousInfMatrix
Definition: DBReader.h:115
rtabmap::DBReader::odomProvided
virtual bool odomProvided() const
Definition: DBReader.h:84
Transform.h
rtabmap::DBReader::_startId
int _startId
Definition: DBReader.h:100
rtabmap::DBReader::_ids
std::set< int > _ids
Definition: DBReader.h:112
rtabmap::DBReader::_stopMapId
int _stopMapId
Definition: DBReader.h:108
UTimer.h
rtabmap::DBReader::_previousStamp
double _previousStamp
Definition: DBReader.h:116
rtabmap::SensorCaptureInfo
Definition: SensorCaptureInfo.h:36
rtabmap::DBReader::_ignoreGoalDelay
bool _ignoreGoalDelay
Definition: DBReader.h:98
rtabmap::DBReader::_stopId
int _stopId
Definition: DBReader.h:101
rtabmap::DBReader::_previousMapId
int _previousMapId
Definition: DBReader.h:114
rtabmap::DBReader::_dbDriver
DBDriver * _dbDriver
Definition: DBReader.h:110
rtabmap::Camera
Definition: Camera.h:43
rtabmap::DBReader::_intermediateNodesIgnored
bool _intermediateNodesIgnored
Definition: DBReader.h:103
rtabmap::DBReader::_timer
UTimer _timer
Definition: DBReader.h:111
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
rtabmap::DBDriver
Definition: DBDriver.h:62
rtabmap_netvlad.init
def init(descriptorDim)
Definition: rtabmap_netvlad.py:30
getPose
Pose3_ getPose(const Expression< PinholeCamera< CALIBRATION > > &cam)
rtabmap::Transform
Definition: Transform.h:41
rtabmap::DBReader::_priorsIgnored
bool _priorsIgnored
Definition: DBReader.h:106
rtabmap::DBReader::_cameraIndex
int _cameraIndex
Definition: DBReader.h:102
rtabmap::DBReader::_startMapId
int _startMapId
Definition: DBReader.h:107
Camera.h
UTimer
Definition: UTimer.h:46
rtabmap::DBReader
Definition: DBReader.h:46
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::DBReader::_featuresIgnored
bool _featuresIgnored
Definition: DBReader.h:105
rtabmap::DBReader::driver
const DBDriver * driver() const
Definition: DBReader.h:87
rtabmap::DBReader::_currentId
std::set< int >::iterator _currentId
Definition: DBReader.h:113
rtabmap::DBReader::_paths
std::list< std::string > _paths
Definition: DBReader.h:96
rtabmap::DBReader::_odometryIgnored
bool _odometryIgnored
Definition: DBReader.h:97


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:09