]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/move_base.launch
amcl tuning
[ros_wild_thumper.git] / launch / move_base.launch
index 88705b986a889311881e490c8ca7496b26754f96..f2fd7330fcbd6d14dc28ab36f0f5cc832fbf315e 100644 (file)
                <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
 
                <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
-               <param name="amcl/base_frame_id" value="base_footprint" />
+               <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.01" />
+                       <!-- 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" />
+                       <!-- 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" />
+                       <!-- 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" />
+                       <!-- 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)" />