CameraRealSense2.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 
33 #include "rtabmap/core/Camera.h"
34 #include "rtabmap/core/Version.h"
35 
36 #include <pcl/pcl_config.h>
37 
38 #ifdef RTABMAP_REALSENSE2
39 #include <librealsense2/rs.hpp>
40 #include <librealsense2/hpp/rs_frame.hpp>
41 #endif
42 
43 
44 namespace rs2
45 {
46  class context;
47  class device;
48  class syncer;
49 }
50 struct rs2_intrinsics;
51 struct rs2_extrinsics;
52 
53 namespace rtabmap
54 {
55 
57  public Camera
58 {
59 public:
60  static bool available();
61 
62 public:
64  const std::string & deviceId = "",
65  float imageRate = 0,
66  const Transform & localTransform = Transform::getIdentity());
67  virtual ~CameraRealSense2();
68 
69  virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
70  virtual bool isCalibrated() const;
71  virtual std::string getSerial() const;
72  virtual bool odomProvided() const;
73  virtual bool getPose(double stamp, Transform & pose, cv::Mat & covariance);
74 
75  // parameters are set during initialization
76  // D400 series
77  void setEmitterEnabled(bool enabled);
78  void setIRFormat(bool enabled, bool useDepthInsteadOfRightImage);
79  void setResolution(int width, int height, int fps = 30);
80  void setDepthResolution(int width, int height, int fps = 30);
81  void setGlobalTimeSync(bool enabled);
82  void publishInterIMU(bool enabled);
88  void setDualMode(bool enabled, const Transform & extrinsics);
89  void setJsonConfig(const std::string & json);
90  // T265 related parameters
91  void setImagesRectified(bool enabled);
92  void setOdomProvided(bool enabled, bool imageStreamsDisabled=false, bool onlyLeftStream = false);
93 
94 #ifdef RTABMAP_REALSENSE2
95 private:
96  void close();
97  void imu_callback(rs2::frame frame);
98  void pose_callback(rs2::frame frame);
99  void frame_callback(rs2::frame frame);
100  void multiple_message_callback(rs2::frame frame);
101  void getPoseAndIMU(
102  const double & stamp,
103  Transform & pose,
104  unsigned int & poseConfidence,
105  IMU & imu,
106  int maxWaitTimeMs = 35);
107 #endif
108 
109 protected:
110  virtual SensorData captureImage(CameraInfo * info = 0);
111 
112 private:
113 #ifdef RTABMAP_REALSENSE2
114  rs2::context ctx_;
115  std::vector<rs2::device> dev_;
116  std::string deviceId_;
117  rs2::syncer syncer_;
118  float depth_scale_meters_;
119  cv::Mat depthBuffer_;
120  cv::Mat rgbBuffer_;
121  CameraModel model_;
122  StereoCameraModel stereoModel_;
123  Transform imuLocalTransform_;
124  std::map<double, cv::Vec3f> accBuffer_;
125  std::map<double, cv::Vec3f> gyroBuffer_;
126  std::map<double, std::pair<Transform, unsigned int> > poseBuffer_; // <stamp, <Pose, confidence: 1=lost, 2=low, 3=high> >
127  UMutex poseMutex_;
128  UMutex imuMutex_;
129  double lastImuStamp_;
130  bool clockSyncWarningShown_;
131  bool imuGlobalSyncWarningShown_;
132 
133  bool emitterEnabled_;
134  bool ir_;
135  bool irDepth_;
136  bool rectifyImages_;
137  bool odometryProvided_;
138  bool odometryImagesDisabled_;
139  bool odometryOnlyLeftStream_;
140  int cameraWidth_;
141  int cameraHeight_;
142  int cameraFps_;
143  int cameraDepthWidth_;
144  int cameraDepthHeight_;
145  int cameraDepthFps_;
146  bool globalTimeSync_;
147  bool publishInterIMU_;
148  bool dualMode_;
149  Transform dualExtrinsics_;
150  std::string jsonConfig_;
151  bool closing_;
152 
153  static Transform realsense2PoseRotation_;
154  static Transform realsense2PoseRotationInv_;
155 #endif
156 };
157 
158 
159 } // namespace rtabmap
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
Definition: UMutex.h:54


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