]> 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 47c23694173cc5818eb6e64947753427b95dfc14..9508c32cff4a8ae83693d511bcf85f0068ab2c3a 100644 (file)
@@ -2,32 +2,50 @@
 <launch>
        <arg name="slam_gmapping" default="false" />
        <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
-
-       <!-- Run the map server -->
-       <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
+       <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 -->
 
        <!-- Run AMCL -->
-       <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
-       <param name="amcl/base_frame_id" value="base_footprint" />
+       <group unless="$(arg nomap)">
+               <!-- Run the map server -->
+               <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
 
-       <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" output="screen" if="$(arg slam_gmapping)">
-               <param name="scan" value="scan" />
-               <param name="delta" value="0.01" />
-               <param name="map_update_interval" value="30" />
-               <param name="linearUpdate" value="0.5" />
-               <param name="angularUpdate" value="0.25" />
-               <param name="xmin" value="-1.0"/>
-               <param name="ymin" value="-1.0"/>
-               <param name="xmax" value="1.0"/>
-               <param name="ymax" value="1.0"/>
-               <param name="odom_frame" value="odom"/>
-       </node>
+               <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
+               <group ns="amcl">
+                       <param name="base_frame_id" value="base_footprint" />
+                       <param name="odom_model_type" value="diff-corrected" />
+                       <!-- Specifies the expected noise in odometry's rotation estimate from the rotational component of the robot's motion. -->
+                       <param name="odom_alpha1" value="0.00001" />
+                       <!-- 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.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.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. -->
+                       <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.1" />
+                       <!-- Minimum allowed number of particles. -->
+                       <param name="min_particles" value="100" />
+               </group>
+       </group>
+
+       <include file="$(find wild_thumper)/launch/gmapping.launch" if="$(arg slam_gmapping)" />
 
-       <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" unless="$(arg slam_gmapping)">
+       <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
+               <param name="base_local_planner" value="$(arg base_local_planner)"/>
+               <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" />
+               <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"/>
        </node>
 </launch>