CameraRGB.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #pragma once
00029 
00030 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
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 // CameraImages
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         std::string getPath() const {return _path;}
00063         unsigned int imagesCount() const;
00064         std::vector<std::string> filenames() const;
00065         bool isImagesRectified() const {return _rectifyImages;}
00066         int getBayerMode() const {return _bayerMode;}
00067         const CameraModel & cameraModel() const {return _model;}
00068 
00069         void setPath(const std::string & dir) {_path=dir;}
00070         void setStartIndex(int index) {_startAt = index;} // negative means last
00071         void setDirRefreshed(bool enabled) {_refreshDir = enabled;}
00072         void setImagesRectified(bool enabled) {_rectifyImages = enabled;}
00073         void setBayerMode(int mode) {_bayerMode = mode;} // -1=disabled (default) 0=BayerBG, 1=BayerGB, 2=BayerRG, 3=BayerGR
00074 
00075         void setTimestamps(bool fileNamesAreStamps, const std::string & filePath = "", bool syncImageRateWithStamps=true)
00076         {
00077                 _filenamesAreTimestamps = fileNamesAreStamps;
00078                 timestampsPath_=filePath;
00079                 syncImageRateWithStamps_ = syncImageRateWithStamps;
00080         }
00081 
00082         void setScanPath(
00083                         const std::string & dir,
00084                         int maxScanPts = 0,
00085                         int downsampleStep = 1,
00086                         float voxelSize = 0.0f,
00087                         int normalsK = 0, // compute normals if > 0
00088                         const Transform & localTransform=Transform::getIdentity())
00089         {
00090                 _scanPath = dir;
00091                 _scanLocalTransform = localTransform;
00092                 _scanMaxPts = maxScanPts;
00093                 _scanDownsampleStep = downsampleStep;
00094                 _scanNormalsK = normalsK;
00095                 _scanVoxelSize = voxelSize;
00096                 if(_scanDownsampleStep>1)
00097                 {
00098                         _scanMaxPts /= _scanDownsampleStep;
00099                 }
00100         }
00101 
00102         void setDepthFromScan(bool enabled, int fillHoles = 1, bool fillHolesFromBorder = false)
00103         {
00104                 _depthFromScan = enabled;
00105                 _depthFromScanFillHoles = fillHoles;
00106                 _depthFromScanFillHolesFromBorder = fillHolesFromBorder;
00107         }
00108 
00109         void setGroundTruthPath(const std::string & filePath, int format = 0)
00110         {
00111                 groundTruthPath_ = filePath;
00112                 _groundTruthFormat = format;
00113         }
00114 
00115         void setDepth(bool isDepth, float depthScaleFactor = 1.0f)
00116         {
00117                 _isDepth = isDepth;
00118                 _depthScaleFactor=depthScaleFactor;
00119         }
00120 
00121 protected:
00122         virtual SensorData captureImage(CameraInfo * info = 0);
00123 
00124 private:
00125         std::string _path;
00126         int _startAt;
00127         // If the list of files in the directory is refreshed
00128         // on each call of takeImage()
00129         bool _refreshDir;
00130         bool _rectifyImages;
00131         int _bayerMode;
00132         bool _isDepth;
00133         float _depthScaleFactor;
00134         int _count;
00135         UDirectory * _dir;
00136         std::string _lastFileName;
00137 
00138         int _countScan;
00139         UDirectory * _scanDir;
00140         std::string _lastScanFileName;
00141         std::string _scanPath;
00142         Transform _scanLocalTransform;
00143         int _scanMaxPts;
00144         int _scanDownsampleStep;
00145         float _scanVoxelSize;
00146         int _scanNormalsK;
00147 
00148         bool _depthFromScan;
00149         int _depthFromScanFillHoles; // <0:horizontal 0:disabled >0:vertical
00150         bool _depthFromScanFillHolesFromBorder;
00151 
00152         bool _filenamesAreTimestamps;
00153         std::string timestampsPath_;
00154         bool syncImageRateWithStamps_;
00155 
00156         std::string groundTruthPath_;
00157         int _groundTruthFormat;
00158 
00159         std::list<double> stamps_;
00160         std::list<Transform> groundTruth_;
00161         CameraModel _model;
00162 
00163         UTimer _captureTimer;
00164         double _captureDelay;
00165 };
00166 
00167 
00168 
00169 
00171 // CameraVideo
00173 class RTABMAP_EXP CameraVideo :
00174         public Camera
00175 {
00176 public:
00177         enum Source{kVideoFile, kUsbDevice};
00178 
00179 public:
00180         CameraVideo(int usbDevice = 0,
00181                         bool rectifyImages = false,
00182                         float imageRate = 0,
00183                         const Transform & localTransform = Transform::getIdentity());
00184         CameraVideo(const std::string & filePath,
00185                         bool rectifyImages = false,
00186                         float imageRate = 0,
00187                         const Transform & localTransform = Transform::getIdentity());
00188         virtual ~CameraVideo();
00189 
00190         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00191         virtual bool isCalibrated() const;
00192         virtual std::string getSerial() const;
00193         int getUsbDevice() const {return _usbDevice;}
00194         const std::string & getFilePath() const {return _filePath;}
00195 
00196 protected:
00197         virtual SensorData captureImage(CameraInfo * info = 0);
00198 
00199 private:
00200         // File type
00201         std::string _filePath;
00202         bool _rectifyImages;
00203 
00204         cv::VideoCapture _capture;
00205         Source _src;
00206 
00207         // Usb camera
00208         int _usbDevice;
00209         std::string _guid;
00210 
00211         CameraModel _model;
00212 };
00213 
00214 
00215 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:15