-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathmap.launch
More file actions
39 lines (32 loc) · 1.88 KB
/
map.launch
File metadata and controls
39 lines (32 loc) · 1.88 KB
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
<launch>
<group ns="rtabmap">
<!-- Odometry -->
<node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="frame_id" type="string" value="base_link"/>
<remap from="rgbd_image" to="rgbd_image"/>
</node>
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start" >
<param name="frame_id" type="string" value="base_link"/>
<param name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_scan" type="bool" value="false"/>
<remap from="odom" to="/odom"/>
<remap from="scan" to="/scan_multi"/>
<remap from="rgb/image" to="/camera/color/image_raw"/>
<remap from="depth/image" to="/camera/aligned_depth_to_color/image_raw"/>
<remap from="rgb/camera_info" to="/camera/color/camera_info"/>
<param name="queue_size" type="int" value="10"/>
<!-- RTAB-Map's parameters -->
<param name="RGBD/NeighborLinkRefining" type="string" value="true"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="RGBD/AngularUpdate" type="string" value="0.01"/>
<param name="RGBD/LinearUpdate" type="string" value="0.01"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Reg/Strategy" type="string" value="1"/> <!-- 1=ICP -->
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Vis/MinInliers" type="string" value="12"/>
<param name="Grid/FromDepth" type="string" value="true"/>
<param name="RGBD/ProximityPathMaxNeighbors" type="string" value="true"/>
</node>
</group>
</launch>