CameraRGBD.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #pragma once
29 
30 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
31 
32 #include "rtabmap/utilite/UMutex.h"
35 #include "rtabmap/core/Camera.h"
36 #include "rtabmap/core/CameraRGB.h"
37 #include "rtabmap/core/Version.h"
38 
39 #include <pcl/pcl_config.h>
40 
41 #ifdef HAVE_OPENNI
42 #if __linux__ && __i386__ && __cplusplus >= 201103L
43 #warning "Openni driver is not available on i386 when building with c++11 support"
44 #else
45 #define RTABMAP_OPENNI
46 #include <pcl/io/openni_camera/openni_depth_image.h>
47 #include <pcl/io/openni_camera/openni_image.h>
48 #endif
49 #endif
50 
51 #include <boost/signals2/connection.hpp>
52 
53 namespace openni
54 {
55 class Device;
56 class VideoStream;
57 }
58 
59 namespace pcl
60 {
61 class Grabber;
62 }
63 
64 namespace libfreenect2
65 {
66 class Freenect2;
67 class Freenect2Device;
68 class SyncMultiFrameListener;
69 class Registration;
70 class PacketPipeline;
71 }
72 
73 namespace rs
74 {
75  class context;
76  class device;
77  namespace slam {
78  class slam;
79  }
80 }
81 
82 namespace rs2
83 {
84  class context;
85  class device;
86  class syncer;
87 }
88 struct rs2_intrinsics;
89 struct rs2_extrinsics;
90 
91 typedef struct _freenect_context freenect_context;
92 typedef struct _freenect_device freenect_device;
93 
96 typedef struct _DepthSpacePoint DepthSpacePoint;
97 typedef struct _ColorSpacePoint ColorSpacePoint;
98 typedef struct tagRGBQUAD RGBQUAD;
100 
101 namespace rtabmap
102 {
103 
105 // CameraOpenNIPCL
108  public Camera
109 {
110 public:
111  static bool available();
112 
113 public:
114  // default local transform z in, x right, y down));
115  CameraOpenni(const std::string & deviceId="",
116  float imageRate = 0,
117  const Transform & localTransform = Transform::getIdentity());
118  virtual ~CameraOpenni();
119 #ifdef RTABMAP_OPENNI
120  void image_cb (
123  float constant);
124 #endif
125 
126  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
127  virtual bool isCalibrated() const;
128  virtual std::string getSerial() const;
129 
130 protected:
131  virtual SensorData captureImage(CameraInfo * info = 0);
132 
133 private:
134  pcl::Grabber* interface_;
135  std::string deviceId_;
136  boost::signals2::connection connection_;
137  cv::Mat depth_;
138  cv::Mat rgb_;
142 };
143 
145 // CameraOpenNICV
148  public Camera
149 {
150 
151 public:
152  static bool available();
153 
154 public:
155  CameraOpenNICV(bool asus = false,
156  float imageRate = 0,
157  const Transform & localTransform = Transform::getIdentity());
158  virtual ~CameraOpenNICV();
159 
160  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
161  virtual bool isCalibrated() const;
162  virtual std::string getSerial() const {return "";} // unknown with OpenCV
163 
164 protected:
165  virtual SensorData captureImage(CameraInfo * info = 0);
166 
167 private:
168  bool _asus;
169  cv::VideoCapture _capture;
170  float _depthFocal;
171 };
172 
174 // CameraOpenNI2
177  public Camera
178 {
179 
180 public:
181  static bool available();
182  static bool exposureGainAvailable();
183  enum Type {kTypeColorDepth, kTypeIRDepth, kTypeIR};
184 
185 public:
186  CameraOpenNI2(const std::string & deviceId = "",
187  Type type = kTypeColorDepth,
188  float imageRate = 0,
189  const Transform & localTransform = Transform::getIdentity());
190  virtual ~CameraOpenNI2();
191 
192  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
193  virtual bool isCalibrated() const;
194  virtual std::string getSerial() const;
195 
196  bool setAutoWhiteBalance(bool enabled);
197  bool setAutoExposure(bool enabled);
198  bool setExposure(int value);
199  bool setGain(int value);
200  bool setMirroring(bool enabled);
201  void setOpenNI2StampsAndIDsUsed(bool used);
202  void setIRDepthShift(int horizontal, int vertical);
203 
204 protected:
205  virtual SensorData captureImage(CameraInfo * info = 0);
206 
207 private:
208 #ifdef RTABMAP_OPENNI2
209  Type _type;
210  openni::Device * _device;
211  openni::VideoStream * _color;
212  openni::VideoStream * _depth;
213  float _depthFx;
214  float _depthFy;
215  std::string _deviceId;
216  bool _openNI2StampsAndIDsUsed;
217  StereoCameraModel _stereoModel;
218  int _depthHShift;
219  int _depthVShift;
220 #endif
221 };
222 
223 
225 // CameraFreenect
227 class FreenectDevice;
228 
230  public Camera
231 {
232 public:
233  static bool available();
234  enum Type {kTypeColorDepth, kTypeIRDepth};
235 
236 public:
237  // default local transform z in, x right, y down));
238  CameraFreenect(int deviceId= 0,
239  Type type = kTypeColorDepth,
240  float imageRate=0.0f,
241  const Transform & localTransform = Transform::getIdentity());
242  virtual ~CameraFreenect();
243 
244  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
245  virtual bool isCalibrated() const;
246  virtual std::string getSerial() const;
247 
248 protected:
249  virtual SensorData captureImage(CameraInfo * info = 0);
250 
251 private:
252 #ifdef RTABMAP_FREENECT
253  int deviceId_;
254  Type type_;
255  freenect_context * ctx_;
256  FreenectDevice * freenectDevice_;
257  StereoCameraModel stereoModel_;
258 #endif
259 };
260 
262 // CameraFreenect2
264 
266  public Camera
267 {
268 public:
269  static bool available();
270 
271  enum Type{
277  kTypeColorIR
278  };
279 
280 public:
281  // default local transform z in, x right, y down));
282  CameraFreenect2(int deviceId= 0,
283  Type type = kTypeDepth2ColorSD,
284  float imageRate=0.0f,
285  const Transform & localTransform = Transform::getIdentity(),
286  float minDepth = 0.3f,
287  float maxDepth = 12.0f,
288  bool bilateralFiltering = true,
289  bool edgeAwareFiltering = true,
290  bool noiseFiltering = true,
291  const std::string & pipelineName = "");
292  virtual ~CameraFreenect2();
293 
294  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
295  virtual bool isCalibrated() const;
296  virtual std::string getSerial() const;
297 
298 protected:
299  virtual SensorData captureImage(CameraInfo * info = 0);
300 
301 private:
302 #ifdef RTABMAP_FREENECT2
303  int deviceId_;
304  Type type_;
305  StereoCameraModel stereoModel_;
306  libfreenect2::Freenect2 * freenect2_;
307  libfreenect2::Freenect2Device *dev_;
308  libfreenect2::SyncMultiFrameListener * listener_;
309  libfreenect2::Registration * reg_;
310  float minKinect2Depth_;
311  float maxKinect2Depth_;
312  bool bilateralFiltering_;
313  bool edgeAwareFiltering_;
314  bool noiseFiltering_;
315  std::string pipelineName_;
316 #endif
317 };
318 
320 // CameraK4W2
322 
324  public Camera
325 {
326 public:
327  static bool available();
328 
329  enum Type {
332  kTypeDepth2ColorHD
333  };
334 
335 public:
336  static const int cDepthWidth = 512;
337  static const int cDepthHeight = 424;
338  static const int cColorWidth = 1920;
339  static const int cColorHeight = 1080;
340 
341 public:
342  // default local transform z in, x right, y down));
343  CameraK4W2(int deviceId = 0, // not used
344  Type type = kTypeDepth2ColorSD,
345  float imageRate = 0.0f,
346  const Transform & localTransform = Transform::getIdentity());
347  virtual ~CameraK4W2();
348 
349  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
350  virtual bool isCalibrated() const;
351  virtual std::string getSerial() const;
352 
353 protected:
354  virtual SensorData captureImage(CameraInfo * info = 0);
355 
356 private:
357  void close();
358 
359 private:
360 #ifdef RTABMAP_K4W2
361  Type type_;
362  IKinectSensor* pKinectSensor_;
363  ICoordinateMapper* pCoordinateMapper_;
364  DepthSpacePoint* pDepthCoordinates_;
365  ColorSpacePoint* pColorCoordinates_;
366  IMultiSourceFrameReader* pMultiSourceFrameReader_;
367  RGBQUAD * pColorRGBX_;
368  INT_PTR hMSEvent;
369  CameraModel colorCameraModel_;
370 #endif
371 };
372 
374 // CameraRealSense
376 class slam_event_handler;
378  public Camera
379 {
380 public:
381  static bool available();
382  enum RGBSource {kColor, kInfrared, kFishEye};
383 
384 public:
385  // default local transform z in, x right, y down));
387  int deviceId = 0,
388  int presetRGB = 0, // 0=best quality, 1=largest image, 2=highest framerate
389  int presetDepth = 0, // 0=best quality, 1=largest image, 2=highest framerate
390  bool computeOdometry = false,
391  float imageRate = 0,
392  const Transform & localTransform = Transform::getIdentity());
393  virtual ~CameraRealSense();
394 
395  void setDepthScaledToRGBSize(bool enabled);
396  void setRGBSource(RGBSource source);
397  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
398  virtual bool isCalibrated() const;
399  virtual std::string getSerial() const;
400  virtual bool odomProvided() const;
401 
402 protected:
403  virtual SensorData captureImage(CameraInfo * info = 0);
404 
405 private:
406 #ifdef RTABMAP_REALSENSE
407  rs::context * ctx_;
408  rs::device * dev_;
409  int deviceId_;
410  int presetRGB_;
411  int presetDepth_;
412  bool computeOdometry_;
413  bool depthScaledToRGBSize_;
414  RGBSource rgbSource_;
415  CameraModel cameraModel_;
416  std::vector<int> rsRectificationTable_;
417 
418  int motionSeq_[2];
419  rs::slam::slam * slam_;
420  UMutex slamLock_;
421 
422  std::map<double, std::pair<cv::Mat, cv::Mat> > bufferedFrames_;
423  std::pair<cv::Mat, cv::Mat> lastSyncFrames_;
424  UMutex dataMutex_;
425  USemaphore dataReady_;
426 #endif
427 };
429 // CameraRealSense2
431 class slam_event_handler;
433  public Camera
434 {
435 public:
436  static bool available();
437 
438 public:
439  // default local transform z in, x right, y down));
441  const std::string & deviceId = "",
442  float imageRate = 0,
443  const Transform & localTransform = Transform::getIdentity());
444  virtual ~CameraRealSense2();
445 
446  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
447  virtual bool isCalibrated() const;
448  virtual std::string getSerial() const;
449 
450  // parameters are set during initialization
451  void setEmitterEnabled(bool enabled);
452  void setIRDepthFormat(bool enabled);
453 
454 protected:
455  virtual SensorData captureImage(CameraInfo * info = 0);
456 
457 private:
458 #ifdef RTABMAP_REALSENSE2
459  rs2::context * ctx_;
460  rs2::device * dev_;
461  std::string deviceId_;
462  rs2::syncer * syncer_;
463  float depth_scale_meters_;
464  rs2_intrinsics * depthIntrinsics_;
465  rs2_intrinsics * rgbIntrinsics_;
466  rs2_extrinsics * depthToRGBExtrinsics_;
467  cv::Mat depthBuffer_;
468  cv::Mat rgbBuffer_;
469  CameraModel model_;
470 
471  bool emitterEnabled_;
472  bool irDepth_;
473 #endif
474 };
475 
476 
478 // CameraRGBDImages
480 class CameraImages;
482  public CameraImages
483 {
484 public:
485  static bool available();
486 
487 public:
489  const std::string & pathRGBImages,
490  const std::string & pathDepthImages,
491  float depthScaleFactor = 1.0f,
492  float imageRate=0.0f,
493  const Transform & localTransform = Transform::getIdentity());
494  virtual ~CameraRGBDImages();
495 
496  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
497  virtual bool isCalibrated() const;
498  virtual std::string getSerial() const;
499 
500  virtual void setStartIndex(int index) {CameraImages::setStartIndex(index);cameraDepth_.setStartIndex(index);} // negative means last
501 
502 protected:
503  virtual SensorData captureImage(CameraInfo * info = 0);
504 
505 private:
507 };
508 
509 } // namespace rtabmap
struct _freenect_device freenect_device
Definition: CameraRGBD.h:92
f
CameraImages cameraDepth_
Definition: CameraRGBD.h:506
Definition: CameraRGBD.h:59
cv::VideoCapture _capture
Definition: CameraRGBD.h:169
Definition: CameraRGBD.h:82
struct IMultiSourceFrameReader IMultiSourceFrameReader
Definition: CameraRGBD.h:99
USemaphore dataReady_
Definition: CameraRGBD.h:141
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
virtual void setStartIndex(int index)
Definition: CameraRGBD.h:500
Definition: UMutex.h:54
const char * source
Definition: lz4hc.h:181
Definition: CameraRGBD.h:73
std::string deviceId_
Definition: CameraRGBD.h:135
struct IKinectSensor IKinectSensor
Definition: CameraRGBD.h:94
boost::signals2::connection connection_
Definition: CameraRGBD.h:136
struct _DepthSpacePoint DepthSpacePoint
Definition: CameraRGBD.h:96
struct _freenect_context freenect_context
Definition: CameraRGBD.h:91
struct tagRGBQUAD RGBQUAD
Definition: CameraRGBD.h:98
virtual std::string getSerial() const
Definition: CameraRGBD.h:162
struct ICoordinateMapper ICoordinateMapper
Definition: CameraRGBD.h:95
pcl::Grabber * interface_
Definition: CameraRGBD.h:134
struct _ColorSpacePoint ColorSpacePoint
Definition: CameraRGBD.h:97


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30