]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/move_base.launch
no duplicate options in global_costmap_params_odom.yaml
[ros_wild_thumper.git] / launch / move_base.launch
index f2fd7330fcbd6d14dc28ab36f0f5cc832fbf315e..c1320cb074dc75a9660c32d8d46420e08003fd2a 100644 (file)
@@ -25,9 +25,9 @@
                        <!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
                        <param name="laser_max_beams" value="50" />
                        <!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. -->
-                       <param name="recovery_alpha_slow" value="0.01" />
+                       <param name="recovery_alpha_slow" value="0.001" />
                        <!-- Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. -->
-                       <param name="recovery_alpha_fast" value="0.2" />
+                       <param name="recovery_alpha_fast" value="0.1" />
                        <!-- Minimum allowed number of particles. -->
                        <param name="min_particles" value="100" />
                </group>
@@ -40,7 +40,7 @@
                <param name="controller_frequency" value="10.0" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
-               <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
+               <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
                <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg nomap)" />
                <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
                <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />