Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #pragma once
00029
00030 #include "rtabmap/core/RtabmapExp.h"
00031
00032 #include <opencv2/highgui/highgui.hpp>
00033 #include "rtabmap/core/Camera.h"
00034 #include "rtabmap/utilite/UTimer.h"
00035 #include <set>
00036 #include <stack>
00037 #include <list>
00038 #include <vector>
00039
00040 class UDirectory;
00041
00042 namespace rtabmap
00043 {
00044
00046
00048 class RTABMAP_EXP CameraImages :
00049 public Camera
00050 {
00051 public:
00052 CameraImages();
00053 CameraImages(
00054 const std::string & path,
00055 float imageRate = 0,
00056 const Transform & localTransform = Transform::getIdentity());
00057 virtual ~CameraImages();
00058
00059 virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00060 virtual bool isCalibrated() const;
00061 virtual std::string getSerial() const;
00062 virtual bool odomProvided() const { return odometry_.size() > 0; }
00063 std::string getPath() const {return _path;}
00064 unsigned int imagesCount() const;
00065 std::vector<std::string> filenames() const;
00066 bool isImagesRectified() const {return _rectifyImages;}
00067 int getBayerMode() const {return _bayerMode;}
00068 const CameraModel & cameraModel() const {return _model;}
00069
00070 void setPath(const std::string & dir) {_path=dir;}
00071 virtual void setStartIndex(int index) {_startAt = index;}
00072 void setDirRefreshed(bool enabled) {_refreshDir = enabled;}
00073 void setImagesRectified(bool enabled) {_rectifyImages = enabled;}
00074 void setBayerMode(int mode) {_bayerMode = mode;}
00075
00076 void setTimestamps(bool fileNamesAreStamps, const std::string & filePath = "", bool syncImageRateWithStamps=true)
00077 {
00078 _filenamesAreTimestamps = fileNamesAreStamps;
00079 _timestampsPath=filePath;
00080 _syncImageRateWithStamps = syncImageRateWithStamps;
00081 }
00082
00083 void setScanPath(
00084 const std::string & dir,
00085 int maxScanPts = 0,
00086 int downsampleStep = 1,
00087 float voxelSize = 0.0f,
00088 int normalsK = 0,
00089 float normalsRadius = 0,
00090 const Transform & localTransform=Transform::getIdentity(),
00091 bool forceGroundNormalsUp = false)
00092 {
00093 _scanPath = dir;
00094 _scanLocalTransform = localTransform;
00095 _scanMaxPts = maxScanPts;
00096 _scanDownsampleStep = downsampleStep;
00097 _scanNormalsK = normalsK;
00098 _scanNormalsRadius = normalsRadius;
00099 _scanVoxelSize = voxelSize;
00100 _scanForceGroundNormalsUp = forceGroundNormalsUp;
00101 }
00102
00103 void setDepthFromScan(bool enabled, int fillHoles = 1, bool fillHolesFromBorder = false)
00104 {
00105 _depthFromScan = enabled;
00106 _depthFromScanFillHoles = fillHoles;
00107 _depthFromScanFillHolesFromBorder = fillHolesFromBorder;
00108 }
00109
00110
00111 void setOdometryPath(const std::string & filePath, int format = 0)
00112 {
00113 _odometryPath = filePath;
00114 _odometryFormat = format;
00115 }
00116
00117
00118 void setGroundTruthPath(const std::string & filePath, int format = 0)
00119 {
00120 _groundTruthPath = filePath;
00121 _groundTruthFormat = format;
00122 }
00123
00124 void setMaxPoseTimeDiff(double diff) {_maxPoseTimeDiff = diff;}
00125 double getMaxPoseTimeDiff() const {return _maxPoseTimeDiff;}
00126
00127 void setDepth(bool isDepth, float depthScaleFactor = 1.0f)
00128 {
00129 _isDepth = isDepth;
00130 _depthScaleFactor=depthScaleFactor;
00131 }
00132
00133 protected:
00134 virtual SensorData captureImage(CameraInfo * info = 0);
00135 bool readPoses(
00136 std::list<Transform> & outputPoses,
00137 std::list<double> & stamps,
00138 const std::string & filePath,
00139 int format,
00140 double maxTimeDiff) const;
00141
00142 private:
00143 std::string _path;
00144 int _startAt;
00145
00146
00147 bool _refreshDir;
00148 bool _rectifyImages;
00149 int _bayerMode;
00150 bool _isDepth;
00151 float _depthScaleFactor;
00152 int _count;
00153 UDirectory * _dir;
00154 std::string _lastFileName;
00155
00156 int _countScan;
00157 UDirectory * _scanDir;
00158 std::string _lastScanFileName;
00159 std::string _scanPath;
00160 Transform _scanLocalTransform;
00161 int _scanMaxPts;
00162 int _scanDownsampleStep;
00163 float _scanVoxelSize;
00164 int _scanNormalsK;
00165 float _scanNormalsRadius;
00166 bool _scanForceGroundNormalsUp;
00167
00168 bool _depthFromScan;
00169 int _depthFromScanFillHoles;
00170 bool _depthFromScanFillHolesFromBorder;
00171
00172 bool _filenamesAreTimestamps;
00173 std::string _timestampsPath;
00174 bool _syncImageRateWithStamps;
00175
00176 std::string _odometryPath;
00177 int _odometryFormat;
00178 std::string _groundTruthPath;
00179 int _groundTruthFormat;
00180 double _maxPoseTimeDiff;
00181
00182 std::list<double> _stamps;
00183 std::list<Transform> odometry_;
00184 std::list<Transform> groundTruth_;
00185 CameraModel _model;
00186
00187 UTimer _captureTimer;
00188 double _captureDelay;
00189 };
00190
00191
00192
00193
00195
00197 class RTABMAP_EXP CameraVideo :
00198 public Camera
00199 {
00200 public:
00201 enum Source{kVideoFile, kUsbDevice};
00202
00203 public:
00204 CameraVideo(int usbDevice = 0,
00205 bool rectifyImages = false,
00206 float imageRate = 0,
00207 const Transform & localTransform = Transform::getIdentity());
00208 CameraVideo(const std::string & filePath,
00209 bool rectifyImages = false,
00210 float imageRate = 0,
00211 const Transform & localTransform = Transform::getIdentity());
00212 virtual ~CameraVideo();
00213
00214 virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00215 virtual bool isCalibrated() const;
00216 virtual std::string getSerial() const;
00217 int getUsbDevice() const {return _usbDevice;}
00218 const std::string & getFilePath() const {return _filePath;}
00219
00220 protected:
00221 virtual SensorData captureImage(CameraInfo * info = 0);
00222
00223 private:
00224
00225 std::string _filePath;
00226 bool _rectifyImages;
00227
00228 cv::VideoCapture _capture;
00229 Source _src;
00230
00231
00232 int _usbDevice;
00233 std::string _guid;
00234
00235 CameraModel _model;
00236 };
00237
00238
00239 }