Skip to content

Commit

Permalink
Merge pull request #79 from LXYYY/feature/tum_rgbd
Browse files Browse the repository at this point in the history
added TUM2 launch and config file
  • Loading branch information
lennarthaller authored Aug 13, 2020
2 parents 9207b77 + a98e183 commit 6ac1abd
Show file tree
Hide file tree
Showing 2 changed files with 91 additions and 0 deletions.
68 changes: 68 additions & 0 deletions orb_slam2/config/TUM2.yaml
Original file line number Diff line number Diff line change
@@ -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
23 changes: 23 additions & 0 deletions ros/launch/orb_slam2_tum2_rgbd.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<launch>
<node name="orb_slam2_rgbd" pkg="orb_slam2_ros"
type="orb_slam2_ros_rgbd" output="screen">

<remap from="camera/depth_registered/image_raw" to="camera/depth/image"/>
<remap from="camera/rgb/image_raw" to="camera/rgb/image_color"/>

<param name="publish_pointcloud" type="bool" value="true" />
<param name="publish_pose" type="bool" value="true" />
<param name="localize_only" type="bool" value="false" />
<param name="reset_map" type="bool" value="false" />

<!-- static parameters -->
<param name="load_map" type="bool" value="false" />
<param name="map_file" type="string" value="map.bin" />
<param name="settings_file" type="string" value="$(find orb_slam2_ros)/orb_slam2/config/TUM2.yaml" />
<param name="voc_file" type="string" value="$(find orb_slam2_ros)/orb_slam2/Vocabulary/ORBvoc.txt" />

<param name="pointcloud_frame_id" type="string" value="map" />
<param name="camera_frame_id" type="string" value="camera_link" />
<param name="min_num_kf_in_map" type="int" value="5" />
</node>
</launch>

0 comments on commit 6ac1abd

Please sign in to comment.