]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/gmapping.launch
asr_vosk: Allow to handle keyword and command in one sentence
[ros_wild_thumper.git] / launch / gmapping.launch
index bf72788729e87865a780f5cc526f1e2e449f6a54..a8a75d41eb657d7de3dd484b18f54ebac0451252 100644 (file)
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <launch>
        <arg name="use_sim_time" default="false" />
 <?xml version="1.0"?>
 <launch>
        <arg name="use_sim_time" default="false" />
-       <param name="/use_sim_time" value="$(arg use_sim_time)"/>
+       <param name="/use_sim_time" value="$(arg use_sim_time)" if="$(arg use_sim_time)"/>
 
        <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
                <param name="scan" value="scan" />
 
        <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
                <param name="scan" value="scan" />
@@ -17,7 +17,7 @@
                <!-- 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+ -->
                <!-- 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="40"/>
+               <param name="minimumScore" value="10"/>
                <!-- 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 -->
                <!-- 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 -->