-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathgmapping-only.launch
More file actions
59 lines (47 loc) · 2.41 KB
/
gmapping-only.launch
File metadata and controls
59 lines (47 loc) · 2.41 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
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
<?xml version="1.0"?>
<launch>
<node pkg="gmapping" type="slam_gmapping" name="gmapping" output="screen" >
<param name="odom_frame" value="odom_combined" />
<param name="base_frame" value="base_link" />
<!-- Process 1 out of every this many scans (set it to a higher number to skip more scans) -->
<param name="throttle_scans" value="1"/>
<param name="map_update_interval" value="5.0"/> <!-- default: 5.0 -->
<!-- The maximum usable range of the laser. A beam is cropped to this value. -->
<param name="maxUrange" value="5.5"/>
<!-- The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free space in the map, set maxUrange < maximum range of the real sensor <= maxRange -->
<param name="maxRange" value="5.5"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="minimumScore" value="50.0"/>
<!-- Number of beams to skip in each scan. -->
<param name="lskip" value="0"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<!-- Process a scan each time the robot translates this far -->
<param name="linearUpdate" value="0.1"/>
<!-- Process a scan each time the robot rotates this far -->
<param name="angularUpdate" value="0.1"/>
<param name="temporalUpdate" value="1.0"/>
<param name="resampleThreshold" value="0.5"/>
<!-- Number of particles in the filter. default 30 -->
<param name="particles" value="30"/>
<!-- Initial map size -->
<param name="xmin" value="-10.0"/>
<param name="ymin" value="-10.0"/>
<param name="xmax" value="10.0"/>
<param name="ymax" value="10.0"/>
<!-- Processing parameters (resolution of the map) -->
<param name="delta" value="0.025"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
</node>
</launch>