-
Notifications
You must be signed in to change notification settings - Fork 3
/
rtab_slam.launch
77 lines (60 loc) · 4.42 KB
/
rtab_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
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
<launch>
<include file="$(find nav_rtabmap)/base_start.launch" />
<arg name="pi/2" value="1.5707963267948966" />
<!-- camera pointing forward -->
<node pkg="tf" type="static_transform_publisher" name="camera2base" args="0.03 0.04 0.185 -$(arg pi/2) 0 -$(arg pi/2) base_link camera_frame 10" />
<group ns="rtabmap">
<node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
<remap from="rgb/image" to="/camera/left/image_rect"/>
<remap from="depth/image" to="/camera/depth"/>
<remap from="rgb/camera_info" to="/camera/left/camera_info"/>
<remap from="rgbd_image" to="rgbd_image"/> <!-- output -->
<!-- all camera topics are exactly synchronized -->
<param name="approx_sync" value="false"/>
</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="false"/>
<param name="subscribe_rgb" type="bool" value="false"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="approx_sync" type="bool" value="true"/>
<param name="queue_size" type="int" value="30"/>
<remap from="odom" to="/odom"/>
<remap from="rgbd_image" to="rgbd_image"/>
<!-- RTAB-Map's parameters -->
<param name="Rtabmap/DetectionRate" type="string" value="0"/> <!-- no filtering, processing done at the speed of incoming data -->
<param name="Rtabmap/TimeThr" type="string" value="0"/> <!-- offline works much faster -->
<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="Vis/MinInliers" type="string" value="5"/>
<param name="Vis/FeatureType" type="string" value="0"/> <!-- use SURF -->
<param name="RGBD/OptimizeMaxError" type="string" value="15.0"/>
<param name="RGBD/NeighborLinkRefining" type="string" value="false"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/> <!-- Referred paper did only global loop closure detection -->
<param name="RGBD/ProximityByTime" type="string" value="false"/>
<param name="Reg/Strategy" type="string" value="0"/> <!-- no real laser scan, so no ICP -->
<param name="Vis/MaxDepth" type="string" value="4.0"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.45"/>
<param name="Kp/TfIdfLikelihoodUsed" type="string" value="false"/>
<param name="Bayes/FullPredictionUpdate" type="string" value="true"/>
<param name="Kp/DetectorStrategy" type="string" value="0"/> <!-- use SURF -->
<param name="Kp/MaxFeatures" type="string" value="400"/>
<param name="SURF/Upright" type="string" value="true"/> <!-- we operate in plane, so no need to calculate rotation -->
<param name="SURF/HessianThreshold" type="string" value="300"/> <!-- helps to get features in low contrast frames -->
<param name="Optimizer/Strategy" type="string" value="0"/> <!-- TORO is the most stable for multi-session mapping -->
<param name="Optimizer/Robust" type="string" value="false"/>
<param name="Optimizer/Iterations" type="string" value="100"/>
<param name="Optimizer/Epsilon" type="string" value="0.00001"/>
<param name="Kp/IncrementalFlann" type="string" value="true"/> <!-- Referred paper didn't use incremental FLANN -->
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Grid/3D" type="string" value="false"/>
<param name="Grid/RayTracing" type="string" value="true"/>
<param name="Grid/RangeMax" type="string" value="3.0"/>
<param name="Grid/MaxGroundHeight" type="string" value="0.05"/>
<param name="Grid/MaxObstacleHeight" type="string" value="0.3"/>
<param name="Grid/FromDepth" type="string" value="true" />
<param name="Mem/SaveDepth16Format" type="string" value="false" />
</node>
</group>
</launch>