CameraRGBD.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 "rtabmap/utilite/UMutex.h"
00035 #include "rtabmap/utilite/USemaphore.h"
00036 #include "rtabmap/core/CameraModel.h"
00037 #include <set>
00038 #include <stack>
00039 #include <list>
00040 #include <vector>
00041 
00042 #include <pcl/io/openni_camera/openni_depth_image.h>
00043 #include <pcl/io/openni_camera/openni_image.h>
00044 
00045 #include <boost/signals2/connection.hpp>
00046 
00047 class UDirectory;
00048 class UTimer;
00049 
00050 namespace openni
00051 {
00052 class Device;
00053 class VideoStream;
00054 }
00055 
00056 namespace pcl
00057 {
00058 class Grabber;
00059 }
00060 
00061 namespace libfreenect2
00062 {
00063 class Freenect2;
00064 class Freenect2Device;
00065 class SyncMultiFrameListener;
00066 class Registration;
00067 class PacketPipeline;
00068 }
00069 
00070 namespace FlyCapture2
00071 {
00072 class Camera;
00073 }
00074 
00075 typedef struct _freenect_context freenect_context;
00076 typedef struct _freenect_device freenect_device;
00077 
00078 namespace rtabmap
00079 {
00080 
00085 class RTABMAP_EXP CameraRGBD
00086 {
00087 public:
00088         virtual ~CameraRGBD();
00089         void takeImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy);
00090 
00091         virtual bool init(const std::string & calibrationFolder = ".") = 0;
00092         virtual bool isCalibrated() const = 0;
00093         virtual std::string getSerial() const = 0;
00094 
00095         //getters
00096         float getImageRate() const {return _imageRate;}
00097         const Transform & getLocalTransform() const {return _localTransform;}
00098         bool isMirroringEnabled() const {return _mirroring;}
00099         bool isColorOnly() const {return _colorOnly;}
00100 
00101         //setters
00102         void setImageRate(float imageRate) {_imageRate = imageRate;}
00103         void setLocalTransform(const Transform & localTransform) {_localTransform= localTransform;}
00104         void setMirroringEnabled(bool mirroring) {_mirroring = mirroring;}
00105         void setColorOnly(bool colorOnly) {_colorOnly = colorOnly;}
00106 
00107 protected:
00113         CameraRGBD(float imageRate = 0,
00114                                 const Transform & localTransform = Transform::getIdentity());
00115 
00119         virtual void captureImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy) = 0;
00120 
00121 private:
00122         float _imageRate;
00123         Transform _localTransform;
00124         bool _mirroring;
00125         bool _colorOnly;
00126         UTimer * _frameRateTimer;
00127 };
00128 
00130 // CameraOpenNIPCL
00132 class RTABMAP_EXP CameraOpenni :
00133         public CameraRGBD
00134 {
00135 public:
00136         static bool available() {return true;}
00137 
00138 public:
00139         // default local transform z in, x right, y down));
00140         CameraOpenni(const std::string & deviceId="",
00141                         float imageRate = 0,
00142                         const Transform & localTransform = Transform::getIdentity());
00143         virtual ~CameraOpenni();
00144 
00145     void image_cb (
00146                 const boost::shared_ptr<openni_wrapper::Image>& rgb,
00147                         const boost::shared_ptr<openni_wrapper::DepthImage>& depth,
00148                         float constant);
00149 
00150     virtual bool init(const std::string & calibrationFolder = ".");
00151     virtual bool isCalibrated() const;
00152     virtual std::string getSerial() const;
00153 
00154 protected:
00155         virtual void captureImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy);
00156 
00157 private:
00158     pcl::Grabber* interface_;
00159     std::string deviceId_;
00160     boost::signals2::connection connection_;
00161     cv::Mat depth_;
00162     cv::Mat rgb_;
00163     float depthConstant_;
00164     UMutex dataMutex_;
00165     USemaphore dataReady_;
00166 };
00167 
00169 // CameraOpenNICV
00171 class RTABMAP_EXP CameraOpenNICV :
00172         public CameraRGBD
00173 {
00174 
00175 public:
00176         static bool available();
00177 
00178 public:
00179         CameraOpenNICV(bool asus = false,
00180                                         float imageRate = 0,
00181                                         const Transform & localTransform = Transform::getIdentity());
00182         virtual ~CameraOpenNICV();
00183 
00184         virtual bool init(const std::string & calibrationFolder = ".");
00185         virtual bool isCalibrated() const;
00186         virtual std::string getSerial() const {return "";} // unknown with OpenCV
00187 
00188 protected:
00189         virtual void captureImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy);
00190 
00191 private:
00192         bool _asus;
00193         cv::VideoCapture _capture;
00194         float _depthFocal;
00195 };
00196 
00198 // CameraOpenNI2
00200 class RTABMAP_EXP CameraOpenNI2 :
00201         public CameraRGBD
00202 {
00203 
00204 public:
00205         static bool available();
00206         static bool exposureGainAvailable();
00207 
00208 public:
00209         CameraOpenNI2(const std::string & deviceId = "",
00210                                         float imageRate = 0,
00211                                         const Transform & localTransform = Transform::getIdentity());
00212         virtual ~CameraOpenNI2();
00213 
00214         virtual bool init(const std::string & calibrationFolder = ".");
00215         virtual bool isCalibrated() const;
00216         virtual std::string getSerial() const;
00217 
00218         bool setAutoWhiteBalance(bool enabled);
00219         bool setAutoExposure(bool enabled);
00220         bool setExposure(int value);
00221         bool setGain(int value);
00222         bool setMirroring(bool enabled);
00223 
00224 protected:
00225         virtual void captureImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy);
00226 
00227 private:
00228         openni::Device * _device;
00229         openni::VideoStream * _color;
00230         openni::VideoStream * _depth;
00231         float _depthFx;
00232         float _depthFy;
00233         std::string _deviceId;
00234 };
00235 
00236 
00238 // CameraFreenect
00240 class FreenectDevice;
00241 
00242 class RTABMAP_EXP CameraFreenect :
00243         public CameraRGBD
00244 {
00245 public:
00246         static bool available();
00247 
00248 public:
00249         // default local transform z in, x right, y down));
00250         CameraFreenect(int deviceId= 0,
00251                                         float imageRate=0.0f,
00252                                         const Transform & localTransform = Transform::getIdentity());
00253         virtual ~CameraFreenect();
00254 
00255         virtual bool init(const std::string & calibrationFolder = ".");
00256         virtual bool isCalibrated() const;
00257         virtual std::string getSerial() const;
00258 
00259 protected:
00260         virtual void captureImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy);
00261 
00262 private:
00263         int deviceId_;
00264         freenect_context * ctx_;
00265         FreenectDevice * freenectDevice_;
00266 };
00267 
00269 // CameraFreenect2
00271 
00272 class RTABMAP_EXP CameraFreenect2 :
00273         public CameraRGBD
00274 {
00275 public:
00276         static bool available();
00277 
00278         enum Type{
00279                 kTypeRGBDepthSD,
00280                 kTypeRGBDepthHD,
00281                 kTypeIRDepth,
00282                 kTypeRGBIR
00283         };
00284 
00285 public:
00286         // default local transform z in, x right, y down));
00287         CameraFreenect2(int deviceId= 0,
00288                                         Type type = kTypeRGBDepthSD,
00289                                         float imageRate=0.0f,
00290                                         const Transform & localTransform = Transform::getIdentity());
00291         virtual ~CameraFreenect2();
00292 
00293         virtual bool init(const std::string & calibrationFolder = ".");
00294         virtual bool isCalibrated() const;
00295         virtual std::string getSerial() const;
00296 
00297 protected:
00298         virtual void captureImage(cv::Mat & rgb, cv::Mat & depth, float & fx, float & fy, float & cx, float & cy);
00299 
00300 private:
00301         int deviceId_;
00302         Type type_;
00303         StereoCameraModel stereoModel_;
00304         libfreenect2::Freenect2 * freenect2_;
00305         libfreenect2::Freenect2Device *dev_;
00306         libfreenect2::PacketPipeline * pipeline_;
00307         libfreenect2::SyncMultiFrameListener * listener_;
00308         libfreenect2::Registration * reg_;
00309 };
00310 
00312 // CameraStereoDC1394
00314 class DC1394Device;
00315 
00316 class RTABMAP_EXP CameraStereoDC1394 :
00317         public CameraRGBD
00318 {
00319 public:
00320         static bool available();
00321 
00322 public:
00323         CameraStereoDC1394( float imageRate=0.0f, const Transform & localTransform = Transform::getIdentity());
00324         virtual ~CameraStereoDC1394();
00325 
00326         virtual bool init(const std::string & calibrationFolder = ".");
00327         virtual bool isCalibrated() const;
00328         virtual std::string getSerial() const;
00329 
00330 protected:
00331         virtual void captureImage(cv::Mat & left, cv::Mat & right, float & fx, float & baseline, float & cx, float & cy);
00332 
00333 private:
00334         DC1394Device *device_;
00335         StereoCameraModel stereoModel_;
00336 };
00337 
00339 // CameraStereoFlyCapture2
00341 class RTABMAP_EXP CameraStereoFlyCapture2 :
00342         public CameraRGBD
00343 {
00344 public:
00345         static bool available();
00346 
00347 public:
00348         CameraStereoFlyCapture2( float imageRate=0.0f, const Transform & localTransform = Transform::getIdentity());
00349         virtual ~CameraStereoFlyCapture2();
00350 
00351         virtual bool init(const std::string & calibrationFolder = ".");
00352         virtual bool isCalibrated() const;
00353         virtual std::string getSerial() const;
00354 
00355 protected:
00356         virtual void captureImage(cv::Mat & left, cv::Mat & right, float & fx, float & baseline, float & cx, float & cy);
00357 
00358 private:
00359         FlyCapture2::Camera * camera_;
00360         void * triclopsCtx_; // TriclopsContext
00361 };
00362 
00363 } // namespace rtabmap


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