mirror of
https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git
synced 2025-09-15 13:08:35 +08:00
43 lines
1.6 KiB
XML
43 lines
1.6 KiB
XML
<launch>
|
|
<arg name="ns" default="tb3_0"/>
|
|
|
|
<!-- Gmapping -->
|
|
<node pkg="gmapping" type="slam_gmapping" name="$(arg ns)_turtlebot3_slam_gmapping" output="screen">
|
|
<param name="base_frame" value="$(arg ns)/base_footprint"/>
|
|
<param name="odom_frame" value="$(arg ns)/odom"/>
|
|
<param name="map_frame" value="$(arg ns)/map"/>
|
|
<param name="map_update_interval" value="2.0"/>
|
|
<param name="maxUrange" value="4.0"/>
|
|
<param name="minimumScore" value="100"/>
|
|
<param name="linearUpdate" value="0.2"/>
|
|
<param name="angularUpdate" value="0.2"/>
|
|
<param name="temporalUpdate" value="0.5"/>
|
|
<param name="delta" value="0.05"/>
|
|
<param name="lskip" value="0"/>
|
|
<param name="particles" value="120"/>
|
|
<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="srr" value="0.01"/>
|
|
<param name="srt" value="0.02"/>
|
|
<param name="str" value="0.01"/>
|
|
<param name="stt" value="0.02"/>
|
|
<param name="resampleThreshold" value="0.5"/>
|
|
<param name="xmin" value="-10.0"/>
|
|
<param name="ymin" value="-10.0"/>
|
|
<param name="xmax" value="10.0"/>
|
|
<param name="ymax" value="10.0"/>
|
|
<param name="llsamplerange" value="0.01"/>
|
|
<param name="llsamplestep" value="0.01"/>
|
|
<param name="lasamplerange" value="0.005"/>
|
|
<param name="lasamplestep" value="0.005"/>
|
|
|
|
<remap from="scan" to="$(arg ns)/scan"/>
|
|
<remap from="map" to="$(arg ns)/map"/>
|
|
</node>
|
|
</launch>
|