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/RtabmapExp.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_EXP 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  DBReader(const std::list<std::string> & databasePaths,
62  float frameRate = 0.0f, // -1 = use Database stamps, 0 = inf
63  bool odometryIgnored = false,
64  bool ignoreGoalDelay = false,
65  bool goalsIgnored = false,
66  int startId = 0,
67  int cameraIndex = -1,
68  int stopId = 0,
69  bool intermediateNodesIgnored = false,
70  bool landmarksIgnored = false,
71  bool featuresIgnored = false,
72  int startMapId = 0,
73  int stopMapId = -1);
74  virtual ~DBReader();
75 
76  virtual bool init(
77  const std::string & calibrationFolder = ".",
78  const std::string & cameraName = "");
79 
80  virtual bool isCalibrated() const;
81  virtual std::string getSerial() const;
82  virtual bool odomProvided() const {return !_odometryIgnored;}
83 
84  const DBDriver * driver() const {return _dbDriver;}
85 
86 protected:
87  virtual SensorData captureImage(CameraInfo * info = 0);
88 
89 private:
90  SensorData getNextData(CameraInfo * info = 0);
91 
92 private:
93  std::list<std::string> _paths;
97  int _startId;
98  int _stopId;
105 
108  std::set<int> _ids;
109  std::set<int>::iterator _currentId;
115 };
116 
117 } /* namespace rtabmap */
118 #endif /* DBREADER_H_ */
Definition: UTimer.h:46
std::list< std::string > _paths
Definition: DBReader.h:93
cv::Mat _previousInfMatrix
Definition: DBReader.h:111
f
bool _landmarksIgnored
Definition: DBReader.h:101
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
bool _goalsIgnored
Definition: DBReader.h:96
const DBDriver * driver() const
Definition: DBReader.h:84
double _previousStamp
Definition: DBReader.h:112
virtual bool odomProvided() const
Definition: DBReader.h:82
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
bool _ignoreGoalDelay
Definition: DBReader.h:95
DBDriver * _dbDriver
Definition: DBReader.h:106
bool _intermediateNodesIgnored
Definition: DBReader.h:100
std::set< int > _ids
Definition: DBReader.h:108
bool _featuresIgnored
Definition: DBReader.h:102
std::set< int >::iterator _currentId
Definition: DBReader.h:109
bool _odometryIgnored
Definition: DBReader.h:94


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