CameraRGBD.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/utilite/UMutex.h"
00033 #include "rtabmap/utilite/USemaphore.h"
00034 #include "rtabmap/core/CameraModel.h"
00035 #include "rtabmap/core/Camera.h"
00036 #include "rtabmap/core/CameraRGB.h"
00037 
00038 #include <pcl/pcl_config.h>
00039 
00040 #ifdef HAVE_OPENNI
00041 #include <pcl/io/openni_camera/openni_depth_image.h>
00042 #include <pcl/io/openni_camera/openni_image.h>
00043 #endif
00044 
00045 #include <boost/signals2/connection.hpp>
00046 
00047 namespace openni
00048 {
00049 class Device;
00050 class VideoStream;
00051 }
00052 
00053 namespace pcl
00054 {
00055 class Grabber;
00056 }
00057 
00058 namespace libfreenect2
00059 {
00060 class Freenect2;
00061 class Freenect2Device;
00062 class SyncMultiFrameListener;
00063 class Registration;
00064 class PacketPipeline;
00065 }
00066 
00067 typedef struct _freenect_context freenect_context;
00068 typedef struct _freenect_device freenect_device;
00069 
00070 namespace rtabmap
00071 {
00072 
00074 // CameraOpenNIPCL
00076 class RTABMAP_EXP CameraOpenni :
00077         public Camera
00078 {
00079 public:
00080         static bool available();
00081 
00082 public:
00083         // default local transform z in, x right, y down));
00084         CameraOpenni(const std::string & deviceId="",
00085                         float imageRate = 0,
00086                         const Transform & localTransform = Transform::getIdentity());
00087         virtual ~CameraOpenni();
00088 #ifdef HAVE_OPENNI
00089     void image_cb (
00090                 const boost::shared_ptr<openni_wrapper::Image>& rgb,
00091                         const boost::shared_ptr<openni_wrapper::DepthImage>& depth,
00092                         float constant);
00093 #endif
00094 
00095     virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00096     virtual bool isCalibrated() const;
00097     virtual std::string getSerial() const;
00098 
00099 protected:
00100         virtual SensorData captureImage(CameraInfo * info = 0);
00101 
00102 private:
00103     pcl::Grabber* interface_;
00104     std::string deviceId_;
00105     boost::signals2::connection connection_;
00106     cv::Mat depth_;
00107     cv::Mat rgb_;
00108     float depthConstant_;
00109     UMutex dataMutex_;
00110     USemaphore dataReady_;
00111 };
00112 
00114 // CameraOpenNICV
00116 class RTABMAP_EXP CameraOpenNICV :
00117         public Camera
00118 {
00119 
00120 public:
00121         static bool available();
00122 
00123 public:
00124         CameraOpenNICV(bool asus = false,
00125                                         float imageRate = 0,
00126                                         const Transform & localTransform = Transform::getIdentity());
00127         virtual ~CameraOpenNICV();
00128 
00129         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00130         virtual bool isCalibrated() const;
00131         virtual std::string getSerial() const {return "";} // unknown with OpenCV
00132 
00133 protected:
00134         virtual SensorData captureImage(CameraInfo * info = 0);
00135 
00136 private:
00137         bool _asus;
00138         cv::VideoCapture _capture;
00139         float _depthFocal;
00140 };
00141 
00143 // CameraOpenNI2
00145 class RTABMAP_EXP CameraOpenNI2 :
00146         public Camera
00147 {
00148 
00149 public:
00150         static bool available();
00151         static bool exposureGainAvailable();
00152 
00153 public:
00154         CameraOpenNI2(const std::string & deviceId = "",
00155                                         float imageRate = 0,
00156                                         const Transform & localTransform = Transform::getIdentity());
00157         virtual ~CameraOpenNI2();
00158 
00159         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00160         virtual bool isCalibrated() const;
00161         virtual std::string getSerial() const;
00162 
00163         bool setAutoWhiteBalance(bool enabled);
00164         bool setAutoExposure(bool enabled);
00165         bool setExposure(int value);
00166         bool setGain(int value);
00167         bool setMirroring(bool enabled);
00168         void setOpenNI2StampsAndIDsUsed(bool used) {_openNI2StampsAndIDsUsed = used;}
00169 
00170 protected:
00171         virtual SensorData captureImage(CameraInfo * info = 0);
00172 
00173 private:
00174         openni::Device * _device;
00175         openni::VideoStream * _color;
00176         openni::VideoStream * _depth;
00177         float _depthFx;
00178         float _depthFy;
00179         std::string _deviceId;
00180         bool _openNI2StampsAndIDsUsed;
00181 };
00182 
00183 
00185 // CameraFreenect
00187 class FreenectDevice;
00188 
00189 class RTABMAP_EXP CameraFreenect :
00190         public Camera
00191 {
00192 public:
00193         static bool available();
00194 
00195 public:
00196         // default local transform z in, x right, y down));
00197         CameraFreenect(int deviceId= 0,
00198                                         float imageRate=0.0f,
00199                                         const Transform & localTransform = Transform::getIdentity());
00200         virtual ~CameraFreenect();
00201 
00202         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00203         virtual bool isCalibrated() const;
00204         virtual std::string getSerial() const;
00205 
00206 protected:
00207         virtual SensorData captureImage(CameraInfo * info = 0);
00208 
00209 private:
00210         int deviceId_;
00211         freenect_context * ctx_;
00212         FreenectDevice * freenectDevice_;
00213 };
00214 
00216 // CameraFreenect2
00218 
00219 class RTABMAP_EXP CameraFreenect2 :
00220         public Camera
00221 {
00222 public:
00223         static bool available();
00224 
00225         enum Type{
00226                 kTypeColor2DepthSD,
00227                 kTypeDepth2ColorSD,
00228                 kTypeDepth2ColorHD,
00229                 kTypeDepth2ColorHD2,
00230                 kTypeIRDepth,
00231                 kTypeColorIR
00232         };
00233 
00234 public:
00235         // default local transform z in, x right, y down));
00236         CameraFreenect2(int deviceId= 0,
00237                                         Type type = kTypeColor2DepthSD,
00238                                         float imageRate=0.0f,
00239                                         const Transform & localTransform = Transform::getIdentity(),
00240                                         float minDepth = 0.3f,
00241                                         float maxDepth = 12.0f,
00242                                         bool bilateralFiltering = true,
00243                                         bool edgeAwareFiltering = true,
00244                                         bool noiseFiltering = true);
00245         virtual ~CameraFreenect2();
00246 
00247         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00248         virtual bool isCalibrated() const;
00249         virtual std::string getSerial() const;
00250 
00251 protected:
00252         virtual SensorData captureImage(CameraInfo * info = 0);
00253 
00254 private:
00255         int deviceId_;
00256         Type type_;
00257         StereoCameraModel stereoModel_;
00258         libfreenect2::Freenect2 * freenect2_;
00259         libfreenect2::Freenect2Device *dev_;
00260         libfreenect2::SyncMultiFrameListener * listener_;
00261         libfreenect2::Registration * reg_;
00262         float minKinect2Depth_;
00263         float maxKinect2Depth_;
00264         bool bilateralFiltering_;
00265         bool edgeAwareFiltering_;
00266         bool noiseFiltering_;
00267 };
00268 
00269 
00271 // CameraRGBDImages
00273 class CameraImages;
00274 class RTABMAP_EXP CameraRGBDImages :
00275         public CameraImages
00276 {
00277 public:
00278         static bool available();
00279 
00280 public:
00281         CameraRGBDImages(
00282                         const std::string & pathRGBImages,
00283                         const std::string & pathDepthImages,
00284                         float depthScaleFactor = 1.0f,
00285                         float imageRate=0.0f,
00286                         const Transform & localTransform = Transform::getIdentity());
00287         virtual ~CameraRGBDImages();
00288 
00289         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00290         virtual bool isCalibrated() const;
00291         virtual std::string getSerial() const;
00292 
00293 protected:
00294         virtual SensorData captureImage(CameraInfo * info = 0);
00295 
00296 private:
00297         CameraImages cameraDepth_;
00298 };
00299 
00300 } // namespace rtabmap


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