]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/move_base.launch
Move config/global_costmap_params_odom.yaml go config/global_costmap_params_utm.yaml
[ros_wild_thumper.git] / launch / move_base.launch
index 9c6755d01a66ed35711e20b0aefe6af19e26d08c..9508c32cff4a8ae83693d511bcf85f0068ab2c3a 100644 (file)
@@ -2,6 +2,7 @@
 <launch>
        <arg name="slam_gmapping" default="false" />
        <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
+       <arg name="global_utm" default="false" />
        <arg name="nomap" default="false" />
        <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
 
@@ -19,9 +20,9 @@
                        <!-- Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion. -->
                        <param name="odom_alpha2" value="0.00001" />
                        <!-- Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion. -->
-                       <param name="odom_alpha3" value="0.01" />
+                       <param name="odom_alpha3" value="0.03" />
                        <!-- Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion. -->
-                       <param name="odom_alpha4" value="0.03" />
+                       <param name="odom_alpha4" value="0.001" />
                        <!-- 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. -->
@@ -40,8 +41,9 @@
                <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_odom.yaml" command="load" if="$(arg nomap)" />
+               <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
+               <rosparam file="$(find wild_thumper)/config/global_costmap_params_nomap.yaml" command="load" if="$(arg nomap)" />
+               <rosparam file="$(find wild_thumper)/config/global_costmap_params_utm.yaml" command="load" if="$(arg global_utm)" />
                <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" />
                <remap from="/cmd_vel" to="move_base/cmd_vel"/>