CameraStereo.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 "rtabmap/core/CameraModel.h"
00033 #include "rtabmap/core/Camera.h"
00034 #include "rtabmap/core/CameraRGB.h"
00035 #include <list>
00036 
00037 namespace FlyCapture2
00038 {
00039 class Camera;
00040 }
00041 
00042 namespace sl
00043 {
00044 namespace zed
00045 {
00046 class Camera;
00047 }
00048 }
00049 
00050 namespace rtabmap
00051 {
00052 
00054 // CameraStereoDC1394
00056 class DC1394Device;
00057 
00058 class RTABMAP_EXP CameraStereoDC1394 :
00059         public Camera
00060 {
00061 public:
00062         static bool available();
00063 
00064 public:
00065         CameraStereoDC1394( float imageRate=0.0f, const Transform & localTransform = Transform::getIdentity());
00066         virtual ~CameraStereoDC1394();
00067 
00068         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00069         virtual bool isCalibrated() const;
00070         virtual std::string getSerial() const;
00071 
00072 protected:
00073         virtual SensorData captureImage(CameraInfo * info = 0);
00074 
00075 private:
00076         DC1394Device *device_;
00077         StereoCameraModel stereoModel_;
00078 };
00079 
00081 // CameraStereoFlyCapture2
00083 class RTABMAP_EXP CameraStereoFlyCapture2 :
00084         public Camera
00085 {
00086 public:
00087         static bool available();
00088 
00089 public:
00090         CameraStereoFlyCapture2( float imageRate=0.0f, const Transform & localTransform = Transform::getIdentity());
00091         virtual ~CameraStereoFlyCapture2();
00092 
00093         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00094         virtual bool isCalibrated() const;
00095         virtual std::string getSerial() const;
00096 
00097 protected:
00098         virtual SensorData captureImage(CameraInfo * info = 0);
00099 
00100 private:
00101         FlyCapture2::Camera * camera_;
00102         void * triclopsCtx_; // TriclopsContext
00103 };
00104 
00106 // CameraStereoZED
00108 class RTABMAP_EXP CameraStereoZed :
00109         public Camera
00110 {
00111 public:
00112         static bool available();
00113 
00114 public:
00115         CameraStereoZed(
00116                         int deviceId,
00117                         int resolution = 2, // 0=HD2K, 1=HD1080, 2=HD720, 3=VGA
00118                         int quality = 1,    // 0=NONE, 1=PERFORMANCE, 2=QUALITY
00119                         int sensingMode = 1,// 0=FULL, 1=RAW
00120                         int confidenceThr = 100,
00121                         bool computeOdometry = false,
00122                         float imageRate=0.0f,
00123                         const Transform & localTransform = Transform::getIdentity());
00124         CameraStereoZed(
00125                         const std::string & svoFilePath,
00126                         int quality = 1,    // 0=NONE, 1=PERFORMANCE, 2=QUALITY
00127                         int sensingMode = 1,// 0=FULL, 1=RAW
00128                         int confidenceThr = 100,
00129                         bool computeOdometry = false,
00130                         float imageRate=0.0f,
00131                         const Transform & localTransform = Transform::getIdentity());
00132         virtual ~CameraStereoZed();
00133 
00134         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00135         virtual bool isCalibrated() const;
00136         virtual std::string getSerial() const;
00137         virtual bool odomProvided() const { return computeOdometry_; }
00138 
00139 protected:
00140         virtual SensorData captureImage(CameraInfo * info = 0);
00141 
00142 private:
00143         sl::zed::Camera * zed_;
00144         StereoCameraModel stereoModel_;
00145         CameraVideo::Source src_;
00146         int usbDevice_;
00147         std::string svoFilePath_;
00148         int resolution_;
00149         int quality_;
00150         int sensingMode_;
00151         int confidenceThr_;
00152         bool computeOdometry_;
00153         bool lost_;
00154 };
00155 
00157 // CameraStereoImages
00159 class CameraImages;
00160 class RTABMAP_EXP CameraStereoImages :
00161         public CameraImages
00162 {
00163 public:
00164         static bool available();
00165 
00166 public:
00167         CameraStereoImages(
00168                         const std::string & pathLeftImages,
00169                         const std::string & pathRightImages,
00170                         bool rectifyImages = false,
00171                         float imageRate=0.0f,
00172                         const Transform & localTransform = Transform::getIdentity());
00173         CameraStereoImages(
00174                         const std::string & pathLeftRightImages,
00175                         bool rectifyImages = false,
00176                         float imageRate=0.0f,
00177                         const Transform & localTransform = Transform::getIdentity());
00178         virtual ~CameraStereoImages();
00179 
00180         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00181         virtual bool isCalibrated() const;
00182         virtual std::string getSerial() const;
00183 
00184 protected:
00185         virtual SensorData captureImage(CameraInfo * info = 0);
00186 
00187 private:
00188         CameraImages * camera2_;
00189         StereoCameraModel stereoModel_;
00190 };
00191 
00192 
00194 // CameraStereoVideo
00196 class CameraImages;
00197 class RTABMAP_EXP CameraStereoVideo :
00198         public Camera
00199 {
00200 public:
00201         static bool available();
00202 
00203 public:
00204         CameraStereoVideo(
00205                         const std::string & path,
00206                         bool rectifyImages = false,
00207                         float imageRate=0.0f,
00208                         const Transform & localTransform = Transform::getIdentity());
00209         CameraStereoVideo(
00210                         int device,
00211                         bool rectifyImages = false,
00212                         float imageRate = 0.0f,
00213                         const Transform & localTransform = Transform::getIdentity());
00214         virtual ~CameraStereoVideo();
00215 
00216         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00217         virtual bool isCalibrated() const;
00218         virtual std::string getSerial() const;
00219 
00220 protected:
00221         virtual SensorData captureImage(CameraInfo * info = 0);
00222 
00223 private:
00224         cv::VideoCapture capture_;
00225         std::string path_;
00226         bool rectifyImages_;
00227         StereoCameraModel stereoModel_;
00228         std::string cameraName_;
00229         CameraVideo::Source src_;
00230         int usbDevice_;
00231 };
00232 
00233 } // namespace rtabmap


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