--- /dev/null
+<?xml version="1.0"?>
+<launch>
+ <arg name="use_sim_time" default="false" />
+ <param name="/use_sim_time" value="$(arg use_sim_time)"/>
+
+ <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
+ <param name="scan" value="scan" />
+ <param name="delta" value="0.01" />
+ <param name="map_update_interval" value="10.0" />
+ <param name="xmin" value="-5.0"/>
+ <param name="ymin" value="-5.0"/>
+ <param name="xmax" value="5.0"/>
+ <param name="ymax" value="5.0"/>
+ <param name="odom_frame" value="odom"/>
+ <!-- The maximum usable range of the laser. A beam is cropped to this value. -->
+ <param name="maxUrange" value="3.5"/>
+ <!-- The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free -->
+ <param name="maxRange" value="10.0"/>
+ <!-- Minimum score for considering the outcome of the scan matching good. Can avoid jumping pose, default: 0.0, max: 600+ -->
+ <param name="minimumScore" value="0"/>
+ <!-- Process a scan each time the robot translates this far -->
+ <param name="linearUpdate" value="0.30"/>
+ <!-- Process a scan each time the robot rotates this far -->
+ <param name="angularUpdate" value="0.436"/> <!-- 25 deg -->
+ <!-- Number of particles in the filter, default: 30 -->
+ <param name="particles" value="65"/>
+ <!-- Odometry error in translation as a function of translation (rho/rho) -->
+ <param name="srr" value="0.01"/>
+ <!-- Odometry error in translation as a function of rotation (rho/theta) -->
+ <param name="srt" value="0.03"/>
+ <!-- Odometry error in rotation as a function of translation (theta/rho) -->
+ <param name="str" value="0.0"/>
+ <!-- Odometry error in rotation as a function of rotation (theta/theta) -->
+ <param name="stt" value="0.0"/>
+ </node>
+</launch>