From a98e183af86202a858941c864652a3c2165c5ef3 Mon Sep 17 00:00:00 2001 From: Mike Xiangyu Liu Date: Thu, 13 Aug 2020 15:49:42 +0800 Subject: [PATCH] added TUM2 launch and config file --- orb_slam2/config/TUM2.yaml | 68 +++++++++++++++++++++++++++ ros/launch/orb_slam2_tum2_rgbd.launch | 23 +++++++++ 2 files changed, 91 insertions(+) create mode 100644 orb_slam2/config/TUM2.yaml create mode 100644 ros/launch/orb_slam2_tum2_rgbd.launch diff --git a/orb_slam2/config/TUM2.yaml b/orb_slam2/config/TUM2.yaml new file mode 100644 index 00000000..4f471f48 --- /dev/null +++ b/orb_slam2/config/TUM2.yaml @@ -0,0 +1,68 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 535.4 +Camera.fy: 539.2 +Camera.cx: 320.1 +Camera.cy: 247.6 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +Camera.width: 640 +Camera.height: 480 + +# Camera frames per second +Camera.fps: 30.0 + +# IR projector baseline times fx (aprox.) +Camera.bf: 40.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 0 + +# Close/Far threshold. Baseline times. +ThDepth: 40.0 + +# Deptmap values factor +DepthMapFactor: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 diff --git a/ros/launch/orb_slam2_tum2_rgbd.launch b/ros/launch/orb_slam2_tum2_rgbd.launch new file mode 100644 index 00000000..b5a9ef14 --- /dev/null +++ b/ros/launch/orb_slam2_tum2_rgbd.launch @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + +