<!-- Run AMCL -->
<group unless="$(arg nomap)">
<!-- Run the map server -->
- <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
+ <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
<include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
<param name="amcl/base_frame_id" value="base_footprint" />
</group>
- <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" output="screen" if="$(arg slam_gmapping)">
+ <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" if="$(arg slam_gmapping)">
<param name="scan" value="scan" />
<param name="delta" value="0.01" />
- <param name="map_update_interval" value="30" />
+ <param name="map_update_interval" value="5.0" />
<param name="linearUpdate" value="0.5" />
<param name="angularUpdate" value="0.25" />
<param name="xmin" value="-5.0"/>
<param name="xmax" value="5.0"/>
<param name="ymax" value="5.0"/>
<param name="odom_frame" value="odom"/>
+ <param name="maxUrange" value="6.0"/>
+ <param name="maxRange" value="8.0"/>
+ <param name="minimumScore" value="200"/>
+ <param name="linearUpdate" value="0.5"/>
+ <param name="particles" value="80"/>
</node>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">