CameraImages.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 #pragma once
29 
30 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
31 
32 #include "rtabmap/core/Camera.h"
33 #include "rtabmap/utilite/UTimer.h"
34 #include <list>
35 
36 class UDirectory;
37 
38 namespace rtabmap
39 {
40 
42  public Camera
43 {
44 public:
45  CameraImages();
47  const std::string & path,
48  float imageRate = 0,
49  const Transform & localTransform = CameraModel::opticalRotation());
50  virtual ~CameraImages();
51 
52  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
53  virtual bool isCalibrated() const;
54  virtual std::string getSerial() const;
55  virtual bool odomProvided() const { return odometry_.size() > 0; }
56  std::string getPath() const {return _path;}
57  unsigned int imagesCount() const;
58  std::vector<std::string> filenames() const;
59  bool isImagesRectified() const {return _rectifyImages;}
60  int getBayerMode() const {return _bayerMode;}
61  const CameraModel & cameraModel() const {return _model;}
62 
63  void setPath(const std::string & dir) {_path=dir;}
64  virtual void setStartIndex(int index) {_startAt = index;} // negative means last
65  virtual void setMaxFrames(int value) {_maxFrames = value;}
66  void setDirRefreshed(bool enabled) {_refreshDir = enabled;}
67  void setImagesRectified(bool enabled) {_rectifyImages = enabled;}
68  void setBayerMode(int mode) {_bayerMode = mode;} // -1=disabled (default) 0=BayerBG, 1=BayerGB, 2=BayerRG, 3=BayerGR
69 
70  void setTimestamps(bool fileNamesAreStamps, const std::string & filePath = "", bool syncImageRateWithStamps=true)
71  {
72  _filenamesAreTimestamps = fileNamesAreStamps;
73  _timestampsPath=filePath;
74  _syncImageRateWithStamps = syncImageRateWithStamps;
75  }
76 
77  void setConfigForEachFrame(bool value)
78  {
79  _hasConfigForEachFrame = value;
80  }
81 
83  const std::string & dir,
84  int maxScanPts = 0,
85  const Transform & localTransform=Transform::getIdentity())
86  {
87  _scanPath = dir;
88  _scanLocalTransform = localTransform;
89  _scanMaxPts = maxScanPts;
90  }
91 
92  void setDepthFromScan(bool enabled, int fillHoles = 1, bool fillHolesFromBorder = false)
93  {
94  _depthFromScan = enabled;
95  _depthFromScanFillHoles = fillHoles;
96  _depthFromScanFillHolesFromBorder = fillHolesFromBorder;
97  }
98 
99  // Format: 0=Raw, 1=RGBD-SLAM, 2=KITTI, 3=TORO, 4=g2o, 5=NewCollege(t,x,y), 6=Malaga Urban GPS, 7=St Lucia INS, 8=Karlsruhe
100  void setOdometryPath(const std::string & filePath, int format = 0)
101  {
102  _odometryPath = filePath;
103  _odometryFormat = format;
104  }
105 
106  // Format: 0=Raw, 1=RGBD-SLAM, 2=KITTI, 3=TORO, 4=g2o, 5=NewCollege(t,x,y), 6=Malaga Urban GPS, 7=St Lucia INS, 8=Karlsruhe
107  void setGroundTruthPath(const std::string & filePath, int format = 0)
108  {
109  _groundTruthPath = filePath;
110  _groundTruthFormat = format;
111  }
112 
113  void setMaxPoseTimeDiff(double diff) {_maxPoseTimeDiff = diff;}
114  double getMaxPoseTimeDiff() const {return _maxPoseTimeDiff;}
115 
116  void setDepth(bool isDepth, float depthScaleFactor = 1.0f)
117  {
118  _isDepth = isDepth;
119  _depthScaleFactor=depthScaleFactor;
120  }
121 
122 protected:
123  virtual SensorData captureImage(CameraInfo * info = 0);
124 
125 private:
126  bool readPoses(
127  std::list<Transform> & outputPoses,
128  std::list<double> & stamps,
129  const std::string & filePath,
130  int format,
131  double maxTimeDiff) const;
132 
133 private:
134  std::string _path;
135  int _startAt;
137  // If the list of files in the directory is refreshed
138  // on each call of takeImage()
142  bool _isDepth;
144  int _count;
147  std::string _lastFileName;
148 
151  std::string _lastScanFileName;
152  std::string _scanPath;
155 
157  int _depthFromScanFillHoles; // <0:horizontal 0:disabled >0:vertical
159 
162  std::string _timestampsPath;
164 
165  std::string _odometryPath;
167  std::string _groundTruthPath;
170 
171  std::list<double> _stamps;
172  std::list<Transform> odometry_;
173  std::list<cv::Mat> covariances_;
174  std::list<Transform> groundTruth_;
176  std::list<CameraModel> _models;
177 
180 };
181 
182 
183 } // namespace rtabmap
int getBayerMode() const
Definition: CameraImages.h:60
std::list< Transform > groundTruth_
Definition: CameraImages.h:174
void setPath(const std::string &dir)
Definition: CameraImages.h:63
Transform _scanLocalTransform
Definition: CameraImages.h:153
Definition: UTimer.h:46
std::list< CameraModel > _models
Definition: CameraImages.h:176
std::string _groundTruthPath
Definition: CameraImages.h:167
std::string _lastFileName
Definition: CameraImages.h:147
void setOdometryPath(const std::string &filePath, int format=0)
Definition: CameraImages.h:100
void setImagesRectified(bool enabled)
Definition: CameraImages.h:67
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
static Transform getIdentity()
Definition: Transform.cpp:380
void setScanPath(const std::string &dir, int maxScanPts=0, const Transform &localTransform=Transform::getIdentity())
Definition: CameraImages.h:82
void setDirRefreshed(bool enabled)
Definition: CameraImages.h:66
void setConfigForEachFrame(bool value)
Definition: CameraImages.h:77
static Transform opticalRotation()
Definition: CameraModel.h:45
void setGroundTruthPath(const std::string &filePath, int format=0)
Definition: CameraImages.h:107
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
std::list< double > _stamps
Definition: CameraImages.h:171
void setBayerMode(int mode)
Definition: CameraImages.h:68
std::string _odometryPath
Definition: CameraImages.h:165
UDirectory * _scanDir
Definition: CameraImages.h:150
std::string _lastScanFileName
Definition: CameraImages.h:151
const CameraModel & cameraModel() const
Definition: CameraImages.h:61
virtual void setStartIndex(int index)
Definition: CameraImages.h:64
void setDepth(bool isDepth, float depthScaleFactor=1.0f)
Definition: CameraImages.h:116
std::list< Transform > odometry_
Definition: CameraImages.h:172
bool _depthFromScanFillHolesFromBorder
Definition: CameraImages.h:158
void setMaxPoseTimeDiff(double diff)
Definition: CameraImages.h:113
void setDepthFromScan(bool enabled, int fillHoles=1, bool fillHolesFromBorder=false)
Definition: CameraImages.h:92
void setTimestamps(bool fileNamesAreStamps, const std::string &filePath="", bool syncImageRateWithStamps=true)
Definition: CameraImages.h:70
virtual bool odomProvided() const
Definition: CameraImages.h:55
std::string _timestampsPath
Definition: CameraImages.h:162
std::string getPath() const
Definition: CameraImages.h:56
bool isImagesRectified() const
Definition: CameraImages.h:59
virtual void setMaxFrames(int value)
Definition: CameraImages.h:65
std::list< cv::Mat > covariances_
Definition: CameraImages.h:173
double getMaxPoseTimeDiff() const
Definition: CameraImages.h:114


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