]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/gmapping.launch
avr/motor_ctrl: Prevent dangerous immediate engine reverse in PID
[ros_wild_thumper.git] / launch / gmapping.launch
1 <?xml version="1.0"?>
2 <launch>
3         <arg name="use_sim_time" default="false" />
4         <param name="/use_sim_time" value="$(arg use_sim_time)"/>
5
6         <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
7                 <param name="scan" value="scan" />
8                 <param name="delta" value="0.01" />
9                 <param name="map_update_interval" value="10.0" />
10                 <param name="xmin" value="-5.0"/>
11                 <param name="ymin" value="-5.0"/>
12                 <param name="xmax" value="5.0"/>
13                 <param name="ymax" value="5.0"/>
14                 <param name="odom_frame" value="odom"/>
15                 <!-- The maximum usable range of the laser. A beam is cropped to this value. -->
16                 <param name="maxUrange" value="3.5"/>
17                 <!-- The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free -->
18                 <param name="maxRange" value="10.0"/>
19                 <!-- Minimum score for considering the outcome of the scan matching good. Can avoid jumping pose, default: 0.0, max: 600+ -->
20                 <param name="minimumScore" value="10"/>
21                 <!-- Process a scan each time the robot translates this far -->
22                 <param name="linearUpdate" value="0.30"/>
23                 <!-- Process a scan each time the robot rotates this far -->
24                 <param name="angularUpdate" value="0.436"/> <!-- 25 deg -->
25                 <!-- Number of particles in the filter, default: 30 -->
26                 <param name="particles" value="70"/>
27                 <!-- Odometry error in translation as a function of translation (rho/rho) -->
28                 <param name="srr" value="0.01"/>
29                 <!-- Odometry error in translation as a function of rotation (rho/theta) -->
30                 <param name="srt" value="0.03"/>
31                 <!-- Odometry error in rotation as a function of translation (theta/rho) -->
32                 <param name="str" value="0.0"/>
33                 <!-- Odometry error in rotation as a function of rotation (theta/theta) -->
34                 <param name="stt" value="0.0"/>
35                 <!-- The number of iterations of the scanmatcher, default: 5 -->
36                 <param name="iterations" value="7"/>
37                 <!-- The sigma of a beam used for likelihood computation, default: 0.075 -->
38                 <param name="lsigma" value="0.085"/>
39         </node>
40 </launch>