root / rgbdslam / rgbd_benchmark / settings_for_evaluation.launch @ 9240aaa3
History | View | Annotate | Download (4.17 KB)
1 | 9240aaa3 | Alex | <launch> |
---|---|---|---|
2 | <!-- this demonstrates the parameters that can be set via the parameter server and their default values --> |
||
3 | <env name="ROSCONSOLE_CONFIG_FILE" value="$(find rgbdslam)/log.conf"/> |
||
4 | <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}]: ${message}"/> |
||
5 | <arg name="debug" default="false"/> |
||
6 | <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/time"/--> |
||
7 | <arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/gdb -ex run -args"/> |
||
8 | <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/xterm -rv -e gdb -ex run -args"/--> |
||
9 | <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/valgrind -DELeTEME-tool=cachegrind -DELETEME-cachegrind-out-file=/tmp/cachegrind.out"/--> |
||
10 | <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/valgrind -DELETEME-leak-check=full "/--> |
||
11 | <arg unless="$(arg debug)" name="launch_prefix" value=""/> |
||
12 | <node pkg="rgbdslam" type="rgbdslam" name="rgbdslam" cwd="node" required="true" output="screen" launch-prefix="$(arg launch_prefix)"> |
||
13 | <param name="config/topic_image_mono" value="/camera/rgb/image_color"/> |
||
14 | <param name="config/topic_image_depth" value="/camera/depth/image"/> |
||
15 | <param name="config/topic_points" value=""/> |
||
16 | <param name="config/wide_topic" value=""/>; |
||
17 | <param name="config/wide_cloud_topic" value=""/>; |
||
18 | <param name="config/fixed_frame_name" value="/map"/> |
||
19 | <param name="config/ground_truth_frame_name" value="/world"/><!--empty string if no ground truth--> |
||
20 | <param name="config/base_frame_name" value="/openni_rgb_optical_frame"/> <!-- /openni_camera for hand-held kinect. For robot, e.g., /base_link --> |
||
21 | <param name="config/fixed_camera" value="true"/> <!--is the kinect fixed with respect to base, or can it be moved--> |
||
22 | <param name="config/start_paused" value="false"/> |
||
23 | <param name="config/store_pointclouds" value="false"/> |
||
24 | <param name="config/subscriber_queue_size" value="9"/> |
||
25 | <param name="config/depth_scaling_factor" value="1.0042723"/> |
||
26 | <!--param name="config/feature_detector_type" value="SURF"/--> |
||
27 | <!--param name="config/feature_extractor_type" value="SURF"/--> |
||
28 | <!--param name="config/bagfile_name" value="/home/endres/tmp/rgbd_datasets/rgbd_dataset_freiburg1_desk.bag"/--> |
||
29 | |||
30 | <param name="config/max_keypoints" value="2000"/> |
||
31 | <param name="config/min_keypoints" value="1500"/> |
||
32 | <param name="config/fast_max_iterations" value="10"/> |
||
33 | <param name="config/surf_max_iterations" value="5"/> |
||
34 | <param name="config/min_translation_meter" value="0.00"/> |
||
35 | <param name="config/min_rotation_degree" value="0.0"/> |
||
36 | <param name="config/min_time_reported" value="0.005"/> |
||
37 | |||
38 | <param name="config/squared_meshing_threshold" value="0.0009"/> |
||
39 | <param name="config/preserve_raster_on_save" value="false"/> |
||
40 | <param name="config/connectivity" value="20"/> |
||
41 | <param name="config/max_connections" value="5"/> |
||
42 | <param name="config/drop_async_frames" value="true"/> |
||
43 | <param name="config/min_matches" value="50"/> |
||
44 | <param name="config/max_dist_for_inliers" value="0.03"/> |
||
45 | <param name="config/ransac_iterations" value="5000"/> |
||
46 | <param name="config/use_flann" value="true"/> |
||
47 | <param name="config/use_gui" value="true"/> |
||
48 | <param name="config/use_glwidget" value="false"/> <!-- incompatible with voxelgrid filter > 0 --> |
||
49 | <param name="config/concurrent_node_construction" value="true"/> |
||
50 | <param name="config/optimizer_iterations" value="1"/> |
||
51 | <param name="config/optimizer_skip_step" value="150000"/> |
||
52 | <param name="config/data_skip_step" value="1"/> |
||
53 | <param name="config/batch_processing" value="true"/> <!--store results and close after bagfile has been processed--> |
||
54 | </node> |
||
55 | <!--include file="$(find openni_camera)/launch/kinect_frames.launch"/--> |
||
56 | </launch> |