CameraRealSense.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 
33 #include "rtabmap/utilite/UMutex.h"
36 #include "rtabmap/core/Camera.h"
37 #include "rtabmap/core/Version.h"
38 
39 namespace rs
40 {
41  class context;
42  class device;
43  namespace slam {
44  class slam;
45  }
46 }
47 
48 namespace rtabmap
49 {
50 
51 class slam_event_handler;
53  public Camera
54 {
55 public:
56  static bool available();
57  enum RGBSource {kColor, kInfrared, kFishEye};
58 
59 public:
60  // default local transform z in, x right, y down));
62  int deviceId = 0,
63  int presetRGB = 0, // 0=best quality, 1=largest image, 2=highest framerate
64  int presetDepth = 0, // 0=best quality, 1=largest image, 2=highest framerate
65  bool computeOdometry = false,
66  float imageRate = 0,
67  const Transform & localTransform = Transform::getIdentity());
68  virtual ~CameraRealSense();
69 
70  void setDepthScaledToRGBSize(bool enabled);
71  void setRGBSource(RGBSource source);
72  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
73  virtual bool isCalibrated() const;
74  virtual std::string getSerial() const;
75  virtual bool odomProvided() const;
76 
77 protected:
78  virtual SensorData captureImage(CameraInfo * info = 0);
79 
80 private:
81 #ifdef RTABMAP_REALSENSE
82  rs::context * ctx_;
83  rs::device * dev_;
84  int deviceId_;
85  int presetRGB_;
86  int presetDepth_;
87  bool computeOdometry_;
88  bool depthScaledToRGBSize_;
89  RGBSource rgbSource_;
90  CameraModel cameraModel_;
91  std::vector<int> rsRectificationTable_;
92 
93  int motionSeq_[2];
94  rs::slam::slam * slam_;
95  UMutex slamLock_;
96 
97  std::map<double, std::pair<cv::Mat, cv::Mat> > bufferedFrames_;
98  std::pair<cv::Mat, cv::Mat> lastSyncFrames_;
99  UMutex dataMutex_;
100  USemaphore dataReady_;
101 #endif
102 };
103 
104 } // namespace rtabmap
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
Definition: UMutex.h:54
const char * source
Definition: lz4hc.h:181


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28