34 #include "rtabmap/core/Version.h" 36 #include <pcl/pcl_config.h> 38 #ifdef RTABMAP_REALSENSE2 39 #include <librealsense2/hpp/rs_frame.hpp> 49 struct rs2_intrinsics;
50 struct rs2_extrinsics;
59 static bool available();
63 const std::string & deviceId =
"",
65 const Transform & localTransform = CameraModel::opticalRotation());
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;
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);
83 void setImagesRectified(
bool enabled);
84 void setOdomProvided(
bool enabled);
86 #ifdef RTABMAP_REALSENSE2 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);
95 unsigned int & poseConfidence,
97 int maxWaitTimeMs = 35);
104 #ifdef RTABMAP_REALSENSE2 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_;
118 std::map<double, cv::Vec3f> accBuffer_;
119 std::map<double, cv::Vec3f> gyroBuffer_;
120 std::map<double, std::pair<Transform, unsigned int> > poseBuffer_;
123 double lastImuStamp_;
124 bool clockSyncWarningShown_;
125 bool imuGlobalSyncWarningShown_;
127 bool emitterEnabled_;
131 bool odometryProvided_;
135 bool globalTimeSync_;
136 bool publishInterIMU_;
139 std::string jsonConfig_;
143 static Transform realsense2PoseRotation_;
144 static Transform realsense2PoseRotationInv_;
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)