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