-
Notifications
You must be signed in to change notification settings - Fork 400
/
bagfiles-without-tf.launch
32 lines (28 loc) · 2.04 KB
/
bagfiles-without-tf.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
<!-- This file demonstrates the use of SIFT features for online SLAM with a Kinect.
The openni driver is started from this file -->
<launch>
<param name="/use_sim_time" value="true"/>
<!-- Load reasonable defaults for the relative pose between cameras -->
<include file="$(find openni_launch)/launch/kinect_frames.launch">
<arg name="camera" value="camera" />
</include>
<arg name="debug" default="false"/>
<arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/xterm -rv -e gdb -ex run -args"/>
<arg unless="$(arg debug)" name="launch_prefix" value=""/>
<node pkg="rgbdslam" type="rgbdslam" name="rgbdslam" cwd="node" required="true" output="screen" launch-prefix="$(arg launch_prefix)">
<!-- Input data settings-->
<param name="config/topic_image_mono" value="/camera/rgb/image_mono"/> <!--could also be color -->
<param name="config/topic_image_depth" value="/camera/depth/image"/>
<param name="config/topic_points" value="/camera/rgb/points"/> <!--if empty, poincloud will be reconstructed from image and depth -->
<param name="config/feature_detector_type" value="SIFTGPU"/>
<param name="config/feature_extractor_type" value="SIFTGPU"/>
<param name="config/nn_distance_ratio" value="0.90"/> <!-- Feature correspondence is valid if distance to nearest neighbour is smaller than this parameter times the distance to the 2nd neighbour -->
<param name="config/max_keypoints" value="600"/><!-- Extract no more than this many keypoints (not honored by SIFTGPU)-->
<param name="config/observability_threshold" value="0.1"/>
<!-- Algortithm settings -->
<param name="config/visualize_mono_depth_overlay" value="false"/> <!-- Show Depth and Monochrome image as overlay in featureflow -->
<param name="config/squared_meshing_threshold" value="0.0004"/>
<param name="config/cloud_creation_skip_step" value="1"/>
<param name="config/use_feature_min_depth" value="false"/>
</node>
</launch>