Browse Source

在进行amcl定位时,修改odom_model_type参数为omni-corrected,odom_alpha值都改小

corvin 4 years ago
parent
commit
6dce2eb80a
1 changed files with 7 additions and 6 deletions
  1. 7 6
      src/robot_navigation/launch/amcl_ydlidar_X2L.launch

+ 7 - 6
src/robot_navigation/launch/amcl_ydlidar_X2L.launch

@@ -4,6 +4,7 @@
   Author: corvin
   Author: corvin
   History:
   History:
     20200326: init this file.
     20200326: init this file.
+    20200804:将odom_mode_type改为omni-corrected,对应odom_alpha参数也更新.
 -->
 -->
 <launch>
 <launch>
   <!-- Run the map server with a map -->
   <!-- Run the map server with a map -->
@@ -17,7 +18,7 @@
 
 
   <!-- Run amcl node -->
   <!-- Run amcl node -->
   <node pkg="amcl" type="amcl" name="robot_amcl">
   <node pkg="amcl" type="amcl" name="robot_amcl">
-    <param name="odom_model_type" value="omni"/>
+    <param name="odom_model_type" value="omni-corrected"/>
 
 
     <param name="base_frame_id" value="base_footprint"/>
     <param name="base_frame_id" value="base_footprint"/>
     <param name="global_frame_id" value="map"/>
     <param name="global_frame_id" value="map"/>
@@ -32,11 +33,11 @@
     <param name="max_particles" value="5000"/>
     <param name="max_particles" value="5000"/>
     <param name="kld_err" value="0.1"/>
     <param name="kld_err" value="0.1"/>
     <param name="kld_z" value="0.99"/>
     <param name="kld_z" value="0.99"/>
-    <param name="odom_alpha1" value="0.2"/>
-    <param name="odom_alpha2" value="0.2"/>
-    <param name="odom_alpha3" value="0.2"/>
-    <param name="odom_alpha4" value="0.2"/>
-    <param name="odom_alpha5" value="0.2"/>
+    <param name="odom_alpha1" value="0.005"/>
+    <param name="odom_alpha2" value="0.005"/>
+    <param name="odom_alpha3" value="0.010"/>
+    <param name="odom_alpha4" value="0.005"/>
+    <param name="odom_alpha5" value="0.003"/>
 
 
     <param name="laser_z_hit" value="0.9"/>
     <param name="laser_z_hit" value="0.9"/>
     <param name="laser_z_short" value="0.05"/>
     <param name="laser_z_short" value="0.05"/>