Camera.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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/SensorData.h"
00034 #include <set>
00035 #include <stack>
00036 #include <list>
00037 #include <vector>
00038 
00039 class UDirectory;
00040 class UTimer;
00041 
00042 namespace rtabmap
00043 {
00044 
00049 class RTABMAP_EXP Camera
00050 {
00051 public:
00052         virtual ~Camera();
00053         cv::Mat takeImage();
00054         virtual bool init() = 0;
00055 
00056         //getters
00057         void getImageSize(unsigned int & width, unsigned int & height);
00058         float getImageRate() const {return _imageRate;}
00059         bool isMirroringEnabled() const {return _mirroring;}
00060 
00061         //setters
00062         void setImageRate(float imageRate) {_imageRate = imageRate;}
00063         void setImageSize(unsigned int width, unsigned int height);
00064         void setMirroringEnabled(bool enabled) {_mirroring = enabled;}
00065 
00066         void setCalibration(const std::string & fileName);
00067         void setCalibration(const cv::Mat & cameraMatrix, const cv::Mat & distorsionCoefficients);
00068         void resetCalibration();
00069 
00070 protected:
00076         Camera(float imageRate = 0,
00077                         unsigned int imageWidth = 0,
00078                         unsigned int imageHeight = 0);
00079 
00080         virtual cv::Mat captureImage() = 0;
00081 
00082 private:
00083         float _imageRate;
00084         unsigned int _imageWidth;
00085         unsigned int _imageHeight;
00086         bool _mirroring;
00087         UTimer * _frameRateTimer;
00088         cv::Mat _k; // camera_matrix
00089         cv::Mat _d; // distorsion_coefficients
00090 };
00091 
00092 
00094 // CameraImages
00096 class RTABMAP_EXP CameraImages :
00097         public Camera
00098 {
00099 public:
00100         CameraImages(const std::string & path,
00101                         int startAt = 1,
00102                         bool refreshDir = false,
00103                         float imageRate = 0,
00104                         unsigned int imageWidth = 0,
00105                         unsigned int imageHeight = 0);
00106         virtual ~CameraImages();
00107 
00108         virtual bool init();
00109         std::string getPath() const {return _path;}
00110 
00111 protected:
00112         virtual cv::Mat captureImage();
00113 
00114 private:
00115         std::string _path;
00116         int _startAt;
00117         // If the list of files in the directory is refreshed
00118         // on each call of takeImage()
00119         bool _refreshDir;
00120         int _count;
00121         UDirectory * _dir;
00122         std::string _lastFileName;
00123 };
00124 
00125 
00126 
00127 
00129 // CameraVideo
00131 class RTABMAP_EXP CameraVideo :
00132         public Camera
00133 {
00134 public:
00135         enum Source{kVideoFile, kUsbDevice};
00136 
00137 public:
00138         CameraVideo(int usbDevice = 0,
00139                         float imageRate = 0,
00140                         unsigned int imageWidth = 0,
00141                         unsigned int imageHeight = 0);
00142         CameraVideo(const std::string & filePath,
00143                         float imageRate = 0,
00144                         unsigned int imageWidth = 0,
00145                         unsigned int imageHeight = 0);
00146         virtual ~CameraVideo();
00147 
00148         virtual bool init();
00149         int getUsbDevice() const {return _usbDevice;}
00150         const std::string & getFilePath() const {return _filePath;}
00151 
00152 protected:
00153         virtual cv::Mat captureImage();
00154 
00155 private:
00156         // File type
00157         std::string _filePath;
00158 
00159         cv::VideoCapture _capture;
00160         Source _src;
00161 
00162         // Usb camera
00163         int _usbDevice;
00164 };
00165 
00166 
00167 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31