Project

General

Profile

Statistics
| Branch: | Revision:

root / rgbdslam / launch / iros_demo.launch @ 9240aaa3

History | View | Annotate | Download (6.38 KB)

1
<!-- This file demonstrates the parameters that can be set via the parameter server.
2
     The settings here typically show the default values (c.f. parameter_server.cpp)
3
     This file strives to enlist all possibilities, to be a good copy-paste source.
4
     In general most options/tags don't need to be altered/used-->
5
<launch>
6
  <include file="$(find openni_camera)/launch/openni_node.launch"/>
7
  <env name="ROSCONSOLE_CONFIG_FILE" value="$(find rgbdslam)/log.conf"/>
8
  <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}]: ${message}"/>
9

    
10
  <arg name="debug" default="false"/>
11
  <!-- Several possibilities to debug -->
12
  <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/gdb -ex run -args"/-->
13
  <arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/xterm -rv -e gdb -ex run -args"/>
14
  <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/valgrind -DELeTEME-tool=cachegrind -DELETEME-cachegrind-out-file=/tmp/cachegrind.out"/-->
15
  <!--arg if="$(arg debug)" name="launch_prefix" value="/usr/bin/valgrind -DELETEME-leak-check=full "/-->
16
  <arg unless="$(arg debug)" name="launch_prefix" value=""/>
17

    
18
  <node pkg="rgbdslam" type="rgbdslam" name="rgbdslam" cwd="node" required="true" output="screen"  launch-prefix="$(arg launch_prefix)"> 
19
    <!-- Input data settings-->
20
    <param name="config/topic_image_mono"              value="/camera/rgb/image_color"/> <!--could also be color -->
21
  	<param name="config/topic_image_depth"             value="/camera/depth/image"/>
22
    <param name="config/topic_points"                  value="/camera/rgb/points"/> <!--if empty, poincloud will be reconstructed from image and depth -->
23
    <param name="config/camera_info_topic"             value="/camera/rgb/camera_info"/>
24
  	<param name="config/subscriber_queue_size"         value="2"/>
25
    <param name="config/drop_async_frames"             value="true"/> <!-- Check association of depth and visual image, reject if not in sync -->
26
    <param name="config/depth_scaling_factor"          value="1.0"/> <!-- to correct bad depth scaling of kinect -->
27

    
28
    <!-- TF information settings -->
29
  	<param name="config/fixed_frame_name"              value="/map"/>
30
    <param name="config/ground_truth_frame_name"       value=""/><!--empty string if no ground truth-->
31
    <param name="config/base_frame_name"               value="/openni_camera"/> <!-- /openni_camera for hand-held kinect. For robot, e.g., /base_link -->
32
    <param name="config/fixed_camera"                  value="true"/> <!--is the kinect fixed with respect to base, or can it be moved (false makes sense only if transform betw. base_frame and openni_camera is sent via tf)-->
33

    
34
    <!-- Visual Features, to activate GPU-based features see CMakeLists.txt -->
35
    <param name="config/feature_detector_type"         value="SURF"/><!-- If SIFTGPU is enabled in CMakeLists.txt -->
36
    <param name="config/feature_extractor_type"        value="SURF"/><!-- If SIFTGPU is enabled in CMakeLists.txt -->
37
    <param name="config/max_keypoints"                 value="1500"/><!-- Extract no more than this many keypoints (not honored by SIFTGPU)-->
38
    <param name="config/min_keypoints"                 value="1000"/><!-- Extract no less than this many ... -->
39
  	<param name="config/surf_max_iterations"           value="3"/>
40

    
41
    <!-- Algortithm settings -->
42
    <param name="config/min_translation_meter"         value="0.1"/><!-- frames with motion less than this, will be omitted -->
43
  	<param name="config/min_rotation_degree"           value="5"/><!-- frames with motion less than this, will be omitted -->
44
    <param name="config/connectivity"                  value="15"/> <!-- compare to how many nodes? 0: always to previous and to root node, -1: only to previous-->
45
    <param name="config/max_connections"               value="8"/><!-- stop after this many succesfully found spation relations -->
46
    <param name="config/min_matches"                   value="50"/><!-- Prune unreliable transformations from too few feature matches -->
47
    <param name="config/ransac_iterations"             value="5000"/><!-- these are fast -->
48
    <param name="config/max_dist_for_inliers"          value="0.03"/> <!--matches considered inliers by ransac-->
49
    <param name="config/use_flann"                     value="true"/> <!-- flann (not avail for ORB) or bruteforcematching -->
50
    <param name="config/optimizer_iterations"          value="2"/><!-- maximum of iterations in online operation (i.e., does not affect the final optimization in batch mode -->
51
    <param name="config/optimizer_skip_step"           value="1"/><!-- optimize every n-th frame -->
52

    
53
    <!-- Visualization Settings -->
54
    <param name="config/squared_meshing_threshold"     value="0.0009"/><!-- don't triangulate over depth jumps -->
55
    <param name="config/use_glwidget"                  value="true"/><!-- 3D visualization needs performance -->
56
    <param name="config/use_gui"                       value="true"/><!-- No visualization, e.g., on robot -->
57
    <param name="config/visualization_skip_step"       value="3"/> <!-- draw only every nth pointcloud row and line -->
58
    <param name="config/show_axis"                     value="true"/>    <!-- do/don't visualize the sensor position -->
59

    
60
    <!-- Misc -->
61
    <param name="config/voxelfilter_size"              value="-1.0"/> <!-- in meter voxefilter displayed and stored pointclouds, incompatible with use_glwidget=true. Set negative to disable-->
62
    <param name="config/individual_cloud_out_topic"    value="/rgbdslam/batch_clouds"/>;
63
    <param name="config/aggregate_cloud_out_topic"     value="/rgbdslam/aggregate_clouds"/>;
64
  	<param name="config/publisher_queue_size"          value="1"/>
65
  	<param name="config/preserve_raster_on_save"       value="false"/>
66
    <param name="config/min_time_reported"             value="0.1"/><!-- for easy runtime analysis -->
67
  	<param name="config/start_paused"                  value="false"/>
68
    <param name="config/store_pointclouds"             value="false"/> <!-- if, e.g., only trajectory is required, setting this to false saves lots of memory -->
69
    <param name="config/bagfile_name"                  value=""/><!-- read data from a bagfile, make sure to enter the right topics above-->
70
    <param name="config/batch_processing"              value="false"/>    <!--store results and close after bagfile has been processed-->
71
    <param name="config/data_skip_step"                value="1"/><!-- skip every n-th frame completely -->
72
  </node>
73
</launch>