Browse Source

更新小车带夹爪的footprint参数,修改amcl中min_particles和max_particles粒子数量,同时减小

corvin rasp melodic 2 years ago
parent
commit
11a3503de1

+ 6 - 6
src/robot_navigation/config/costmap_common_params.yaml

@@ -1,4 +1,4 @@
-# Description: 代价地图通用配置文件各参数意义如下:
+# Description: 代价地图通用配置文件,各参数意义如下:
 #   obstacle_range: 最大障碍物检测范围,超过该范围不认为是障碍物
 #   raytrace_range: 检测自由空间的最大范围
 #   robot_radius: 机器人本体的半径大小,单位:米,圆形机器人使用.
@@ -14,16 +14,16 @@
 # History:
 #   20180410:init this file.
 #   20200413:更新参数并更新注释信息.
-#   20220920:更新inflation_layer配置参数.
+#   20220920:更新inflation_layer配置参数,更新带夹爪机器人的footprint参数.
 
 #单独圆形机器人的底盘半径参数,不带前面夹爪
 #robot_radius: 0.10
 
 #圆形机器人前面带上下移动夹爪的参数
-footprint: [[ 0.30,  0.00],[ 0.30,  0.055],[ 0.10,  0.055],
-            [ 0.09,  0.09],[ 0.00,  0.13],[-0.09,  0.09],
-            [-0.13,  0.00],[-0.09, -0.09],[ 0.00, -0.13],
-            [ 0.09, -0.09],[ 0.10, -0.055],[ 0.30, -0.055]]
+footprint: [[ 0.30,  0.00],[ 0.30,  0.07],[ 0.08,  0.07],
+            [ 0.07,  0.08],[ 0.00,  0.11],[-0.07,  0.08],
+            [-0.11,  0.00],[-0.07, -0.08],[ 0.00, -0.11],
+            [ 0.07, -0.08],[ 0.08, -0.07],[ 0.30, -0.07]]
 
 map_type: costmap
 

+ 2 - 2
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -44,11 +44,11 @@ DWAPlannerROS:
   vth_samples: 20
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 40.0
+  path_distance_bias: 48.0
   goal_distance_bias: 20.0
   occdist_scale: 0.02
   forward_point_distance: 0.2
-  stop_time_buffer: 0.4
+  stop_time_buffer: 0.6
   scaling_speed: 0.25
   max_scaling_factor: 0.2
 

+ 1 - 1
src/robot_navigation/config/local_costmap_params.yaml

@@ -20,7 +20,7 @@ local_costmap:
     update_frequency: 3.0
     publish_frequency: 3.0
 
-    #static_map: false
+    static_map: false
     rolling_window: true
     width: 1.5
     height: 1.5

+ 18 - 12
src/robot_navigation/launch/amcl_dwa.launch

@@ -1,5 +1,10 @@
 <!--
   Description:使用EAI的X2L雷达进行amcl定位,加载地图进行自动导航,这里加载的局部路径规划算法是dwa.
+    odom_alpha1:从旋转角度估计机器人里程计的旋转噪声
+    odom_alpha2:机器人平移分量中的里程计旋转噪音,噪声在机器人左右两边分布
+    odom_alpha3:机器人平移过程中的里程计平移噪音,沿着机器人前进方向分布
+    odom_alpha4:机器人旋转过程中的里程计平移噪音,斜角方向上的运动噪声
+    odom_alpha5:从旋转角度考虑机器人里程计的旋转噪声
   Author: corvin
   History:
     20200326:init this file.
@@ -7,20 +12,20 @@
     20220810:在启动amcl算法进行自动导航时,先将robot_bringup.launch启动.
 -->
 <launch>
-  <!-- startup robot bringup -->
+  <!--(1) startup robot bringup -->
   <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
 
-  <!-- Run the map server with a map -->
+  <!--(2) Run the map server with loading a map -->
   <node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/test_map.yaml" />
 
-  <!-- startup ydlidar X2L node -->
+  <!--(3) startup ydlidar X2L node -->
   <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
 
-  <!-- startup move_base node -->
+  <!--(4) startup move_base node -->
   <include file="$(find robot_navigation)/launch/move_base.launch" />
 
-  <!-- Run amcl node -->
-  <node pkg="amcl" type="amcl" name="robot_amcl">
+  <!--(5) Run amcl node -->
+  <node pkg="amcl" type="amcl" name="robot_amcl" output="screen">
     <param name="odom_model_type" value="diff-corrected"/>
 
     <param name="base_frame_id"   value="base_footprint"/>
@@ -34,14 +39,15 @@
     <param name="transform_tolerance" value="3"/>
     <param name="gui_publish_rate" value="10.0"/>
     <param name="laser_max_beams" value="300"/>
-    <param name="min_particles" value="500"/>
-    <param name="max_particles" value="2500"/>
+    <param name="min_particles" value="100"/>
+    <param name="max_particles" value="2000"/>
     <param name="kld_err" value="0.1"/>
     <param name="kld_z"   value="0.99"/>
-    <param name="odom_alpha1" value="0.2"/>
+
+    <param name="odom_alpha1" value="0.1"/>
     <param name="odom_alpha2" value="0.1"/>
     <param name="odom_alpha3" value="0.1"/>
-    <param name="odom_alpha4" value="0.2"/>
+    <param name="odom_alpha4" value="0.1"/>
     <param name="odom_alpha5" value="0.0"/>
 
     <param name="save_pose_rate" value="0.5" />
@@ -54,7 +60,7 @@
     <param name="laser_lambda_short" value="0.1"/>
     <param name="laser_model_type" value="likelihood_field"/>
     <param name="laser_model_type" value="beam"/>
-    <param name="laser_min_range"  value="0.14"/>
+    <param name="laser_min_range"  value="0.12"/>
     <param name="laser_max_range"  value="7.0"/>
     <param name="laser_likelihood_max_dist" value="2.0"/>
     <param name="update_min_d" value="0.05"/>
@@ -65,6 +71,6 @@
     <param name="recovery_alpha_fast" value="0.1"/>
   </node>
 
-  <!-- startup view_navigation.launch -->
+  <!--(6) startup view_navigation.launch -->
   <include file="$(find robot_navigation)/launch/view_navigation.launch" />
 </launch>

+ 2 - 2
src/robot_navigation/launch/move_base.launch

@@ -1,6 +1,6 @@
 <!--
   Description:
-    move base package launch file, load config file for slam,config file list below:
+    move base package load config file for slam,config file list below:
     (1)costmap_common_params.yaml -global_costmap
     (2)costmap_common_params.yaml -local_costmap
     (3)local_costmap_params.yaml
@@ -12,7 +12,7 @@
     20190728:init this file.
 -->
 <launch>
-  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
+  <node pkg="move_base" type="move_base" name="move_base" respawn="true" output="screen" clear_params="true">
     <param name="controller_frequency" value="7"/>
     <param name="controller_patiente"  value="3.0"/>
 

+ 1 - 1
src/robot_navigation/launch/ydlidar_X2L.launch

@@ -18,7 +18,7 @@
     <param name="angle_min"    type="double" value="-180" />
     <param name="angle_max"    type="double" value="180" />
     <param name="range_min"    type="double" value="0.1" />
-    <param name="range_max"    type="double" value="8.0" />
+    <param name="range_max"    type="double" value="7.0" />
     <param name="ignore_array" type="string" value="" />
 
     <param name="frequency"    type="double" value="7"/>

+ 30 - 56
src/robot_navigation/rviz/view_navigation.rviz

@@ -6,7 +6,7 @@ Panels:
       Expanded:
         - /Odometry1/Shape1
       Splitter Ratio: 0.5083333253860474
-    Tree Height: 311
+    Tree Height: 510
   - Class: rviz/Selection
     Name: Selection
   - Class: rviz/Tool Properties
@@ -52,61 +52,19 @@ Visualization Manager:
       Reference Frame: <Fixed Frame>
       Value: true
     - Class: rviz/TF
-      Enabled: true
+      Enabled: false
       Frame Timeout: 15
       Frames:
         All Enabled: true
-        back_wheel_link:
-          Value: true
-        base_footprint:
-          Value: true
-        base_imu_link:
-          Value: true
-        base_link:
-          Value: true
-        front_wheel_link:
-          Value: true
-        left_wheel_link:
-          Value: true
-        lidar:
-          Value: true
-        map:
-          Value: true
-        odom_combined:
-          Value: true
-        right_wheel_link:
-          Value: true
-        servo_left_right_link:
-          Value: true
-        servo_up_down_link:
-          Value: true
       Marker Scale: 0.6000000238418579
       Name: TF
       Show Arrows: true
       Show Axes: true
       Show Names: true
       Tree:
-        map:
-          odom_combined:
-            base_footprint:
-              base_link:
-                back_wheel_link:
-                  {}
-                base_imu_link:
-                  {}
-                front_wheel_link:
-                  {}
-                left_wheel_link:
-                  {}
-                lidar:
-                  {}
-                right_wheel_link:
-                  {}
-                servo_left_right_link:
-                  servo_up_down_link:
-                    {}
+        {}
       Update Interval: 0
-      Value: true
+      Value: false
     - Alpha: 0.800000011920929
       Class: rviz/Map
       Color Scheme: map
@@ -307,10 +265,10 @@ Visualization Manager:
       Name: Odometry
       Position Tolerance: 0.05000000074505806
       Shape:
-        Alpha: 0.5
+        Alpha: 0.6000000238418579
         Axes Length: 1
         Axes Radius: 0.10000000149011612
-        Color: 255; 0; 0
+        Color: 199; 199; 99
         Head Length: 0.05000000074505806
         Head Radius: 0.05000000074505806
         Shaft Length: 0.05000000074505806
@@ -342,6 +300,22 @@ Visualization Manager:
       Topic: /move_base/TebLocalPlannerROS/local_plan
       Unreliable: false
       Value: true
+    - Alpha: 1
+      Arrow Length: 0.30000001192092896
+      Axes Length: 0.30000001192092896
+      Axes Radius: 0.009999999776482582
+      Class: rviz/PoseArray
+      Color: 255; 25; 0
+      Enabled: false
+      Head Length: 0.07000000029802322
+      Head Radius: 0.029999999329447746
+      Name: PoseArray
+      Shaft Length: 0.23000000417232513
+      Shaft Radius: 0.009999999776482582
+      Shape: Arrow (Flat)
+      Topic: /particlecloud
+      Unreliable: false
+      Value: false
   Enabled: true
   Global Options:
     Background Color: 45; 32; 41
@@ -369,7 +343,7 @@ Visualization Manager:
   Value: true
   Views:
     Current:
-      Angle: 0
+      Angle: -0.04500005766749382
       Class: rviz/TopDownOrtho
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.05999999865889549
@@ -379,19 +353,19 @@ Visualization Manager:
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.009999999776482582
-      Scale: 121.00311279296875
+      Scale: 145.46278381347656
       Target Frame: <Fixed Frame>
       Value: TopDownOrtho (rviz)
-      X: 2.0725924968719482
-      Y: 0.9657533764839172
+      X: 2.021449089050293
+      Y: 1.3053816556930542
     Saved: ~
 Window Geometry:
   Displays:
     collapsed: true
-  Height: 815
+  Height: 880
   Hide Left Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000251fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000004400000251000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000280fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000280000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650100000000000004d40000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004d40000028000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a000002c1fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000044000002c1000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000280fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000280000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650100000000000004d40000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004d4000002c100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
@@ -401,5 +375,5 @@ Window Geometry:
   Views:
     collapsed: true
   Width: 1236
-  X: 14
-  Y: 102
+  X: 10
+  Y: 42