34 #include "rtabmap/core/Version.h" 36 #include <pcl/pcl_config.h> 38 #ifdef RTABMAP_REALSENSE2 39 #include <librealsense2/rs.hpp> 40 #include <librealsense2/hpp/rs_frame.hpp> 50 struct rs2_intrinsics;
51 struct rs2_extrinsics;
60 static bool available();
64 const std::string & deviceId =
"",
66 const Transform & localTransform = Transform::getIdentity());
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);
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);
91 void setImagesRectified(
bool enabled);
92 void setOdomProvided(
bool enabled,
bool imageStreamsDisabled=
false,
bool onlyLeftStream =
false);
94 #ifdef RTABMAP_REALSENSE2 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);
102 const double & stamp,
104 unsigned int & poseConfidence,
106 int maxWaitTimeMs = 35);
113 #ifdef RTABMAP_REALSENSE2 115 std::vector<rs2::device> dev_;
116 std::string deviceId_;
118 float depth_scale_meters_;
119 cv::Mat depthBuffer_;
124 std::map<double, cv::Vec3f> accBuffer_;
125 std::map<double, cv::Vec3f> gyroBuffer_;
126 std::map<double, std::pair<Transform, unsigned int> > poseBuffer_;
129 double lastImuStamp_;
130 bool clockSyncWarningShown_;
131 bool imuGlobalSyncWarningShown_;
133 bool emitterEnabled_;
137 bool odometryProvided_;
138 bool odometryImagesDisabled_;
139 bool odometryOnlyLeftStream_;
143 int cameraDepthWidth_;
144 int cameraDepthHeight_;
146 bool globalTimeSync_;
147 bool publishInterIMU_;
150 std::string jsonConfig_;
153 static Transform realsense2PoseRotation_;
154 static Transform realsense2PoseRotationInv_;
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)