CameraRGB.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 <opencv2/highgui/highgui.hpp>
33 #include "rtabmap/core/Camera.h"
34 #include "rtabmap/utilite/UTimer.h"
35 #include <set>
36 #include <stack>
37 #include <list>
38 #include <vector>
39 
40 class UDirectory;
41 
42 namespace rtabmap
43 {
44 
46 // CameraImages
49  public Camera
50 {
51 public:
52  CameraImages();
54  const std::string & path,
55  float imageRate = 0,
56  const Transform & localTransform = Transform::getIdentity());
57  virtual ~CameraImages();
58 
59  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
60  virtual bool isCalibrated() const;
61  virtual std::string getSerial() const;
62  virtual bool odomProvided() const { return odometry_.size() > 0; }
63  std::string getPath() const {return _path;}
64  unsigned int imagesCount() const;
65  std::vector<std::string> filenames() const;
66  bool isImagesRectified() const {return _rectifyImages;}
67  int getBayerMode() const {return _bayerMode;}
68  const CameraModel & cameraModel() const {return _model;}
69 
70  void setPath(const std::string & dir) {_path=dir;}
71  virtual void setStartIndex(int index) {_startAt = index;} // negative means last
72  void setDirRefreshed(bool enabled) {_refreshDir = enabled;}
73  void setImagesRectified(bool enabled) {_rectifyImages = enabled;}
74  void setBayerMode(int mode) {_bayerMode = mode;} // -1=disabled (default) 0=BayerBG, 1=BayerGB, 2=BayerRG, 3=BayerGR
75 
76  void setTimestamps(bool fileNamesAreStamps, const std::string & filePath = "", bool syncImageRateWithStamps=true)
77  {
78  _filenamesAreTimestamps = fileNamesAreStamps;
79  _timestampsPath=filePath;
80  _syncImageRateWithStamps = syncImageRateWithStamps;
81  }
82 
84  const std::string & dir,
85  int maxScanPts = 0,
86  int downsampleStep = 1,
87  float voxelSize = 0.0f,
88  int normalsK = 0, // compute normals if > 0
89  float normalsRadius = 0, // compute normals if > 0
90  const Transform & localTransform=Transform::getIdentity(),
91  bool forceGroundNormalsUp = false)
92  {
93  _scanPath = dir;
94  _scanLocalTransform = localTransform;
95  _scanMaxPts = maxScanPts;
96  _scanDownsampleStep = downsampleStep;
97  _scanNormalsK = normalsK;
98  _scanNormalsRadius = normalsRadius;
99  _scanVoxelSize = voxelSize;
100  _scanForceGroundNormalsUp = forceGroundNormalsUp;
101  }
102 
103  void setDepthFromScan(bool enabled, int fillHoles = 1, bool fillHolesFromBorder = false)
104  {
105  _depthFromScan = enabled;
106  _depthFromScanFillHoles = fillHoles;
107  _depthFromScanFillHolesFromBorder = fillHolesFromBorder;
108  }
109 
110  // 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
111  void setOdometryPath(const std::string & filePath, int format = 0)
112  {
113  _odometryPath = filePath;
114  _odometryFormat = format;
115  }
116 
117  // 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
118  void setGroundTruthPath(const std::string & filePath, int format = 0)
119  {
120  _groundTruthPath = filePath;
121  _groundTruthFormat = format;
122  }
123 
124  void setMaxPoseTimeDiff(double diff) {_maxPoseTimeDiff = diff;}
125  double getMaxPoseTimeDiff() const {return _maxPoseTimeDiff;}
126 
127  void setDepth(bool isDepth, float depthScaleFactor = 1.0f)
128  {
129  _isDepth = isDepth;
130  _depthScaleFactor=depthScaleFactor;
131  }
132 
133 protected:
134  virtual SensorData captureImage(CameraInfo * info = 0);
135  bool readPoses(
136  std::list<Transform> & outputPoses,
137  std::list<double> & stamps,
138  const std::string & filePath,
139  int format,
140  double maxTimeDiff) const;
141 
142 private:
143  std::string _path;
144  int _startAt;
145  // If the list of files in the directory is refreshed
146  // on each call of takeImage()
150  bool _isDepth;
152  int _count;
154  std::string _lastFileName;
155 
158  std::string _lastScanFileName;
159  std::string _scanPath;
167 
169  int _depthFromScanFillHoles; // <0:horizontal 0:disabled >0:vertical
171 
173  std::string _timestampsPath;
175 
176  std::string _odometryPath;
178  std::string _groundTruthPath;
181 
182  std::list<double> _stamps;
183  std::list<Transform> odometry_;
184  std::list<Transform> groundTruth_;
186 
189 };
190 
191 
192 
193 
195 // CameraVideo
198  public Camera
199 {
200 public:
201  enum Source{kVideoFile, kUsbDevice};
202 
203 public:
204  CameraVideo(int usbDevice = 0,
205  bool rectifyImages = false,
206  float imageRate = 0,
207  const Transform & localTransform = Transform::getIdentity());
208  CameraVideo(const std::string & filePath,
209  bool rectifyImages = false,
210  float imageRate = 0,
211  const Transform & localTransform = Transform::getIdentity());
212  virtual ~CameraVideo();
213 
214  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
215  virtual bool isCalibrated() const;
216  virtual std::string getSerial() const;
217  int getUsbDevice() const {return _usbDevice;}
218  const std::string & getFilePath() const {return _filePath;}
219 
220 protected:
221  virtual SensorData captureImage(CameraInfo * info = 0);
222 
223 private:
224  // File type
225  std::string _filePath;
227 
228  cv::VideoCapture _capture;
230 
231  // Usb camera
233  std::string _guid;
234 
236 };
237 
238 
239 } // namespace rtabmap
int getBayerMode() const
Definition: CameraRGB.h:67
std::list< Transform > groundTruth_
Definition: CameraRGB.h:184
void setPath(const std::string &dir)
Definition: CameraRGB.h:70
Transform _scanLocalTransform
Definition: CameraRGB.h:160
Definition: UTimer.h:46
std::string _groundTruthPath
Definition: CameraRGB.h:178
cv::VideoCapture _capture
Definition: CameraRGB.h:228
std::string _lastFileName
Definition: CameraRGB.h:154
void setOdometryPath(const std::string &filePath, int format=0)
Definition: CameraRGB.h:111
void setImagesRectified(bool enabled)
Definition: CameraRGB.h:73
static Transform getIdentity()
Definition: Transform.cpp:364
void setDirRefreshed(bool enabled)
Definition: CameraRGB.h:72
bool _scanForceGroundNormalsUp
Definition: CameraRGB.h:166
void setScanPath(const std::string &dir, int maxScanPts=0, int downsampleStep=1, float voxelSize=0.0f, int normalsK=0, float normalsRadius=0, const Transform &localTransform=Transform::getIdentity(), bool forceGroundNormalsUp=false)
Definition: CameraRGB.h:83
std::string _guid
Definition: CameraRGB.h:233
CameraModel _model
Definition: CameraRGB.h:185
void setGroundTruthPath(const std::string &filePath, int format=0)
Definition: CameraRGB.h:118
int getUsbDevice() const
Definition: CameraRGB.h:217
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
std::list< double > _stamps
Definition: CameraRGB.h:182
void setBayerMode(int mode)
Definition: CameraRGB.h:74
std::string _odometryPath
Definition: CameraRGB.h:176
UDirectory * _scanDir
Definition: CameraRGB.h:157
std::string _lastScanFileName
Definition: CameraRGB.h:158
CameraModel _model
Definition: CameraRGB.h:235
const CameraModel & cameraModel() const
Definition: CameraRGB.h:68
virtual void setStartIndex(int index)
Definition: CameraRGB.h:71
void setDepth(bool isDepth, float depthScaleFactor=1.0f)
Definition: CameraRGB.h:127
std::list< Transform > odometry_
Definition: CameraRGB.h:183
bool _depthFromScanFillHolesFromBorder
Definition: CameraRGB.h:170
void setMaxPoseTimeDiff(double diff)
Definition: CameraRGB.h:124
void setDepthFromScan(bool enabled, int fillHoles=1, bool fillHolesFromBorder=false)
Definition: CameraRGB.h:103
void setTimestamps(bool fileNamesAreStamps, const std::string &filePath="", bool syncImageRateWithStamps=true)
Definition: CameraRGB.h:76
virtual bool odomProvided() const
Definition: CameraRGB.h:62
UDirectory * _dir
Definition: CameraRGB.h:153
std::string _timestampsPath
Definition: CameraRGB.h:173
std::string _path
Definition: CameraRGB.h:143
std::string getPath() const
Definition: CameraRGB.h:63
bool isImagesRectified() const
Definition: CameraRGB.h:66
const std::string & getFilePath() const
Definition: CameraRGB.h:218
std::string _scanPath
Definition: CameraRGB.h:159
double getMaxPoseTimeDiff() const
Definition: CameraRGB.h:125
std::string _filePath
Definition: CameraRGB.h:225


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30