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 #include "rtabmap/core/Version.h"
00038 
00039 #include <pcl/pcl_config.h>
00040 
00041 #ifdef HAVE_OPENNI
00042 #if __linux__ && __i386__ && __cplusplus >= 201103L
00043 #warning "Openni driver is not available on i386 when building with c++11 support"
00044 #else
00045 #define RTABMAP_OPENNI
00046 #include <pcl/io/openni_camera/openni_depth_image.h>
00047 #include <pcl/io/openni_camera/openni_image.h>
00048 #endif
00049 #endif
00050 
00051 #include <boost/signals2/connection.hpp>
00052 
00053 namespace openni
00054 {
00055 class Device;
00056 class VideoStream;
00057 }
00058 
00059 namespace pcl
00060 {
00061 class Grabber;
00062 }
00063 
00064 namespace libfreenect2
00065 {
00066 class Freenect2;
00067 class Freenect2Device;
00068 class SyncMultiFrameListener;
00069 class Registration;
00070 class PacketPipeline;
00071 }
00072 
00073 namespace rs
00074 {
00075         class context;
00076         class device;
00077         namespace slam {
00078         class slam;
00079         }
00080 }
00081 
00082 namespace rs2
00083 {
00084         class context;
00085         class device;
00086         class syncer;
00087 }
00088 struct rs2_intrinsics;
00089 struct rs2_extrinsics;
00090 
00091 typedef struct _freenect_context freenect_context;
00092 typedef struct _freenect_device freenect_device;
00093 
00094 typedef struct IKinectSensor IKinectSensor;
00095 typedef struct ICoordinateMapper ICoordinateMapper;
00096 typedef struct _DepthSpacePoint DepthSpacePoint;
00097 typedef struct _ColorSpacePoint ColorSpacePoint;
00098 typedef struct tagRGBQUAD RGBQUAD;
00099 typedef struct IMultiSourceFrameReader IMultiSourceFrameReader;
00100 
00101 namespace rtabmap
00102 {
00103 
00105 // CameraOpenNIPCL
00107 class RTABMAP_EXP CameraOpenni :
00108         public Camera
00109 {
00110 public:
00111         static bool available();
00112 
00113 public:
00114         // default local transform z in, x right, y down));
00115         CameraOpenni(const std::string & deviceId="",
00116                         float imageRate = 0,
00117                         const Transform & localTransform = Transform::getIdentity());
00118         virtual ~CameraOpenni();
00119 #ifdef RTABMAP_OPENNI
00120     void image_cb (
00121                 const boost::shared_ptr<openni_wrapper::Image>& rgb,
00122                         const boost::shared_ptr<openni_wrapper::DepthImage>& depth,
00123                         float constant);
00124 #endif
00125 
00126     virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00127     virtual bool isCalibrated() const;
00128     virtual std::string getSerial() const;
00129 
00130 protected:
00131         virtual SensorData captureImage(CameraInfo * info = 0);
00132 
00133 private:
00134     pcl::Grabber* interface_;
00135     std::string deviceId_;
00136     boost::signals2::connection connection_;
00137     cv::Mat depth_;
00138     cv::Mat rgb_;
00139     float depthConstant_;
00140     UMutex dataMutex_;
00141     USemaphore dataReady_;
00142 };
00143 
00145 // CameraOpenNICV
00147 class RTABMAP_EXP CameraOpenNICV :
00148         public Camera
00149 {
00150 
00151 public:
00152         static bool available();
00153 
00154 public:
00155         CameraOpenNICV(bool asus = false,
00156                                         float imageRate = 0,
00157                                         const Transform & localTransform = Transform::getIdentity());
00158         virtual ~CameraOpenNICV();
00159 
00160         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00161         virtual bool isCalibrated() const;
00162         virtual std::string getSerial() const {return "";} // unknown with OpenCV
00163 
00164 protected:
00165         virtual SensorData captureImage(CameraInfo * info = 0);
00166 
00167 private:
00168         bool _asus;
00169         cv::VideoCapture _capture;
00170         float _depthFocal;
00171 };
00172 
00174 // CameraOpenNI2
00176 class RTABMAP_EXP CameraOpenNI2 :
00177         public Camera
00178 {
00179 
00180 public:
00181         static bool available();
00182         static bool exposureGainAvailable();
00183         enum Type {kTypeColorDepth, kTypeIRDepth, kTypeIR};
00184 
00185 public:
00186         CameraOpenNI2(const std::string & deviceId = "",
00187                                         Type type = kTypeColorDepth,
00188                                         float imageRate = 0,
00189                                         const Transform & localTransform = Transform::getIdentity());
00190         virtual ~CameraOpenNI2();
00191 
00192         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00193         virtual bool isCalibrated() const;
00194         virtual std::string getSerial() const;
00195 
00196         bool setAutoWhiteBalance(bool enabled);
00197         bool setAutoExposure(bool enabled);
00198         bool setExposure(int value);
00199         bool setGain(int value);
00200         bool setMirroring(bool enabled);
00201         void setOpenNI2StampsAndIDsUsed(bool used);
00202         void setIRDepthShift(int horizontal, int vertical);
00203 
00204 protected:
00205         virtual SensorData captureImage(CameraInfo * info = 0);
00206 
00207 private:
00208 #ifdef RTABMAP_OPENNI2
00209         Type _type;
00210         openni::Device * _device;
00211         openni::VideoStream * _color;
00212         openni::VideoStream * _depth;
00213         float _depthFx;
00214         float _depthFy;
00215         std::string _deviceId;
00216         bool _openNI2StampsAndIDsUsed;
00217         StereoCameraModel _stereoModel;
00218         int _depthHShift;
00219         int _depthVShift;
00220 #endif
00221 };
00222 
00223 
00225 // CameraFreenect
00227 class FreenectDevice;
00228 
00229 class RTABMAP_EXP CameraFreenect :
00230         public Camera
00231 {
00232 public:
00233         static bool available();
00234         enum Type {kTypeColorDepth, kTypeIRDepth};
00235 
00236 public:
00237         // default local transform z in, x right, y down));
00238         CameraFreenect(int deviceId= 0,
00239                                         Type type = kTypeColorDepth,
00240                                         float imageRate=0.0f,
00241                                         const Transform & localTransform = Transform::getIdentity());
00242         virtual ~CameraFreenect();
00243 
00244         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00245         virtual bool isCalibrated() const;
00246         virtual std::string getSerial() const;
00247 
00248 protected:
00249         virtual SensorData captureImage(CameraInfo * info = 0);
00250 
00251 private:
00252 #ifdef RTABMAP_FREENECT
00253         int deviceId_;
00254         Type type_;
00255         freenect_context * ctx_;
00256         FreenectDevice * freenectDevice_;
00257         StereoCameraModel stereoModel_;
00258 #endif
00259 };
00260 
00262 // CameraFreenect2
00264 
00265 class RTABMAP_EXP CameraFreenect2 :
00266         public Camera
00267 {
00268 public:
00269         static bool available();
00270 
00271         enum Type{
00272                 kTypeColor2DepthSD,
00273                 kTypeDepth2ColorSD,
00274                 kTypeDepth2ColorHD,
00275                 kTypeDepth2ColorHD2,
00276                 kTypeIRDepth,
00277                 kTypeColorIR
00278         };
00279 
00280 public:
00281         // default local transform z in, x right, y down));
00282         CameraFreenect2(int deviceId= 0,
00283                                         Type type = kTypeDepth2ColorSD,
00284                                         float imageRate=0.0f,
00285                                         const Transform & localTransform = Transform::getIdentity(),
00286                                         float minDepth = 0.3f,
00287                                         float maxDepth = 12.0f,
00288                                         bool bilateralFiltering = true,
00289                                         bool edgeAwareFiltering = true,
00290                                         bool noiseFiltering = true,
00291                                         const std::string & pipelineName = "");
00292         virtual ~CameraFreenect2();
00293 
00294         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00295         virtual bool isCalibrated() const;
00296         virtual std::string getSerial() const;
00297 
00298 protected:
00299         virtual SensorData captureImage(CameraInfo * info = 0);
00300 
00301 private:
00302 #ifdef RTABMAP_FREENECT2
00303         int deviceId_;
00304         Type type_;
00305         StereoCameraModel stereoModel_;
00306         libfreenect2::Freenect2 * freenect2_;
00307         libfreenect2::Freenect2Device *dev_;
00308         libfreenect2::SyncMultiFrameListener * listener_;
00309         libfreenect2::Registration * reg_;
00310         float minKinect2Depth_;
00311         float maxKinect2Depth_;
00312         bool bilateralFiltering_;
00313         bool edgeAwareFiltering_;
00314         bool noiseFiltering_;
00315         std::string pipelineName_;
00316 #endif
00317 };
00318 
00320 // CameraK4W2
00322 
00323 class RTABMAP_EXP CameraK4W2 :
00324         public Camera
00325 {
00326 public:
00327         static bool available();
00328 
00329         enum Type {
00330                 kTypeColor2DepthSD,
00331                 kTypeDepth2ColorSD,
00332                 kTypeDepth2ColorHD
00333         };
00334 
00335 public:
00336         static const int        cDepthWidth = 512;
00337         static const int        cDepthHeight = 424;
00338         static const int        cColorWidth = 1920;
00339         static const int        cColorHeight = 1080;
00340 
00341 public:
00342         // default local transform z in, x right, y down));
00343         CameraK4W2(int deviceId = 0, // not used
00344                 Type type = kTypeDepth2ColorSD,
00345                 float imageRate = 0.0f,
00346                 const Transform & localTransform = Transform::getIdentity());
00347         virtual ~CameraK4W2();
00348 
00349         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00350         virtual bool isCalibrated() const;
00351         virtual std::string getSerial() const;
00352 
00353 protected:
00354         virtual SensorData captureImage(CameraInfo * info = 0);
00355 
00356 private:
00357         void close();
00358 
00359 private:
00360 #ifdef RTABMAP_K4W2
00361         Type type_;
00362         IKinectSensor*          pKinectSensor_;
00363         ICoordinateMapper*      pCoordinateMapper_;
00364         DepthSpacePoint*        pDepthCoordinates_;
00365         ColorSpacePoint*        pColorCoordinates_;
00366         IMultiSourceFrameReader* pMultiSourceFrameReader_;
00367         RGBQUAD * pColorRGBX_;
00368         INT_PTR hMSEvent;
00369         CameraModel colorCameraModel_;
00370 #endif
00371 };
00372 
00374 // CameraRealSense
00376 class slam_event_handler;
00377 class RTABMAP_EXP CameraRealSense :
00378         public Camera
00379 {
00380 public:
00381         static bool available();
00382         enum RGBSource {kColor, kInfrared, kFishEye};
00383 
00384 public:
00385         // default local transform z in, x right, y down));
00386         CameraRealSense(
00387                 int deviceId = 0,
00388                 int presetRGB = 0, // 0=best quality, 1=largest image, 2=highest framerate
00389                 int presetDepth = 0, // 0=best quality, 1=largest image, 2=highest framerate
00390                 bool computeOdometry = false,
00391                 float imageRate = 0,
00392                 const Transform & localTransform = Transform::getIdentity());
00393         virtual ~CameraRealSense();
00394 
00395         void setDepthScaledToRGBSize(bool enabled);
00396         void setRGBSource(RGBSource source);
00397         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00398         virtual bool isCalibrated() const;
00399         virtual std::string getSerial() const;
00400         virtual bool odomProvided() const;
00401 
00402 protected:
00403         virtual SensorData captureImage(CameraInfo * info = 0);
00404 
00405 private:
00406 #ifdef RTABMAP_REALSENSE
00407         rs::context * ctx_;
00408         rs::device * dev_;
00409         int deviceId_;
00410         int presetRGB_;
00411         int presetDepth_;
00412         bool computeOdometry_;
00413         bool depthScaledToRGBSize_;
00414         RGBSource rgbSource_;
00415         CameraModel cameraModel_;
00416         std::vector<int> rsRectificationTable_;
00417 
00418         int motionSeq_[2];
00419         rs::slam::slam * slam_;
00420         UMutex slamLock_;
00421 
00422         std::map<double, std::pair<cv::Mat, cv::Mat> > bufferedFrames_;
00423         std::pair<cv::Mat, cv::Mat> lastSyncFrames_;
00424         UMutex dataMutex_;
00425         USemaphore dataReady_;
00426 #endif
00427 };
00429 // CameraRealSense2
00431 class slam_event_handler;
00432 class RTABMAP_EXP CameraRealSense2 :
00433         public Camera
00434 {
00435 public:
00436         static bool available();
00437 
00438 public:
00439         // default local transform z in, x right, y down));
00440         CameraRealSense2(
00441                 const std::string & deviceId = "",
00442                 float imageRate = 0,
00443                 const Transform & localTransform = Transform::getIdentity());
00444         virtual ~CameraRealSense2();
00445 
00446         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00447         virtual bool isCalibrated() const;
00448         virtual std::string getSerial() const;
00449 
00450         // parameters are set during initialization
00451         void setEmitterEnabled(bool enabled);
00452         void setIRDepthFormat(bool enabled);
00453 
00454 protected:
00455         virtual SensorData captureImage(CameraInfo * info = 0);
00456 
00457 private:
00458 #ifdef RTABMAP_REALSENSE2
00459         rs2::context * ctx_;
00460         rs2::device * dev_;
00461         std::string deviceId_;
00462         rs2::syncer * syncer_;
00463         float depth_scale_meters_;
00464         rs2_intrinsics * depthIntrinsics_;
00465         rs2_intrinsics * rgbIntrinsics_;
00466         rs2_extrinsics * depthToRGBExtrinsics_;
00467         cv::Mat depthBuffer_;
00468         cv::Mat rgbBuffer_;
00469         CameraModel model_;
00470 
00471         bool emitterEnabled_;
00472         bool irDepth_;
00473 #endif
00474 };
00475 
00476 
00478 // CameraRGBDImages
00480 class CameraImages;
00481 class RTABMAP_EXP CameraRGBDImages :
00482         public CameraImages
00483 {
00484 public:
00485         static bool available();
00486 
00487 public:
00488         CameraRGBDImages(
00489                         const std::string & pathRGBImages,
00490                         const std::string & pathDepthImages,
00491                         float depthScaleFactor = 1.0f,
00492                         float imageRate=0.0f,
00493                         const Transform & localTransform = Transform::getIdentity());
00494         virtual ~CameraRGBDImages();
00495 
00496         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00497         virtual bool isCalibrated() const;
00498         virtual std::string getSerial() const;
00499 
00500         virtual void setStartIndex(int index) {CameraImages::setStartIndex(index);cameraDepth_.setStartIndex(index);} // negative means last
00501 
00502 protected:
00503         virtual SensorData captureImage(CameraInfo * info = 0);
00504 
00505 private:
00506         CameraImages cameraDepth_;
00507 };
00508 
00509 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:19