/
slam.launch
52 lines (43 loc) · 2.58 KB
/
slam.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
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
<!-- -->
<launch>
<arg name="prefix" default="racecar"/>
<arg name="localization" default="false"/>
<arg name="database_path" default="~/.ros/rtabmap_$(arg prefix).db"/>
<arg name="odom_correction" default="true"/>
<arg if="$(arg localization)" name="rtabmap_args" value="--Mem/IncrementalMemory false"/>
<arg unless="$(arg localization)" name="rtabmap_args" value="--delete_db_on_start"/>
<group ns="$(arg prefix)">
<!-- Mapping: -->
<node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="$(arg rtabmap_args) --uerror">
<param name="database_path" type="string" value="$(arg database_path)"/>
<param name="frame_id" type="string" value="$(arg prefix)/base_footprint"/>
<param name="map_frame_id" type="string" value="$(arg prefix)/map"/>
<param name="odom_frame_id" type="string" value="$(arg prefix)/odom"/>
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgb" type="bool" value="false"/>
<param name="subscribe_scan" type="bool" value="true"/>
<param name="use_action_for_goal" type="bool" value="true"/>
<remap from="scan" to="scan"/>
<remap from="grid_map" to="map"/>
<remap from="move_base" to="move_base"/>
<param name="queue_size" type="int" value="10"/>
<param name="approx_sync" type="bool" value="true"/>
<!-- RTAB-Map's parameters -->
<param name="RGBD/NeighborLinkRefining" type="string" value="$(arg odom_correction)"/>
<param name="RGBD/ProximityBySpace" type="string" value="$(arg odom_correction)"/>
<param name="RGBD/AngularUpdate" type="string" value="0.01"/>
<param name="RGBD/LinearUpdate" type="string" value="0.01"/>
<param name="Grid/FromDepth" type="string" value="false"/> <!-- occupancy grid from lidar -->
<param name="Grid/CellSize" type="string" value="0.1"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Reg/Strategy" type="string" value="1"/> <!-- 1=ICP -->
<param name="DbSqlite3/InMemory" type="string" value="true"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="RGBD/ProximityMaxGraphDepth" type="string" value="0"/>
<param name="RGBD/SavedLocalizationIgnored" type="string" value="true"/>
<!-- ICP parameters -->
<param name="Icp/VoxelSize" type="string" value="0.05"/>
<param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/>
</node>
</group>
</launch>