12345678910111213141516171819202122232425262728293031323334353637383940414243 |
- <launch>
- <param name="use_sim_time" value="false"/>
- <!-- startup rplidar node -->
- <include file="$(find rplidar_ros)/launch/rplidar.launch" />
- <!-- startup move_base node -->
- <include file="$(find carebot_navigation)/launch/move_base.launch" />
- <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
- <param name="map_update_interval" value="5.0"/>
- <param name="maxUrange" value="7.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="lskip" value="0"/>
- <param name="minimumScore" value="50"/>
- <param name="srr" value="0.1"/>
- <param name="srt" value="0.2"/>
- <param name="str" value="0.1"/>
- <param name="stt" value="0.2"/>
- <param name="linearUpdate" value="1.0"/>
- <param name="angularUpdate" value="0.5"/>
- <param name="temporalUpdate" value="3.0"/>
- <param name="resampleThreshold" value="0.5"/>
- <param name="particles" value="30"/>
- <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="delta" value="0.05"/>
- <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>
|