Bläddra i källkod

优化自动导航参数,可以在地图中稳定移动

corvin rasp melodic 2 år sedan
förälder
incheckning
f9489b4b4d

+ 17 - 5
src/robot_navigation/config/base_global_planner_params.yaml

@@ -1,15 +1,21 @@
 # Description: 三轮全向移动小车的全局路径规划参数配置文件.
+#    allow_unknown:是否允许路径规划器在未知区域创建路径,同时若只设置该参数为true还不行,
+#        还要在costmap_commons_params.yaml中设置track_unknown_space参数也为true才行.
+#    default_tolerance:当设置的目的地被障碍物占据时,以该参数为半径寻找到最近的点作为新目的地点.
+#    use_quadratic:true将使用二次函数近似函数计算potential,false使用更加简单的计算方式,节省硬件资源.
+#    outline_map:在全局代价地图外设置为致命障碍,如果配置全局代价地图不是静态地图(rolling window),
+#        那么就需要配置该参数为false.
 # Author: corvin
 # History:
-#   20200821: init this file.
+#   20200821:init this config file.
+#   20220920:更新全局路径配置参数.
 
-# Global Planner Selection
 base_global_planner: "global_planner/GlobalPlanner"
 
 GlobalPlanner:
     allow_unknown: false
     default_tolerance: 0.2
-    visualize_potential: false
+    
     use_dijkstra: true
     use_quadratic: true
     use_grid_path: false
@@ -17,6 +23,12 @@ GlobalPlanner:
     lethal_cost: 253
     neutral_cost: 50
     cost_factor: 3
-    publish_potential: true
-    orientation_mode: 0
+
+    #debug param
+    publish_potential: false
+    visualize_potential: false
+
+    orientation_mode: 1
     orientation_window_size: 1
+
+    outline_map: true

+ 13 - 11
src/robot_navigation/config/costmap_common_params.yaml

@@ -1,5 +1,4 @@
-# Description:
-# 代价地图通用配置文件,各参数意义如下:
+# Description: 代价地图通用配置文件,各参数意义如下:
 #   obstacle_range: 最大障碍物检测范围,超过该范围不认为是障碍物
 #   raytrace_range: 检测自由空间的最大范围
 #   robot_radius: 机器人本体的半径大小,单位:米,圆形机器人使用.
@@ -10,23 +9,25 @@
 #   cost_scaling_factor:用于将inflation计算cost的比例因数,该参数
 #     越大,越不把这个inflating看着移动的cost.
 #   map_type:如果想要3D视图的就用voxel,2D视图的就用costmap参数.
-#   observation_sources: 观察源是激光雷达
+#   observation_sources:观察源是激光雷达
 # Author: corvin
 # History:
 #   20180410:init this file.
 #   20200413:更新参数并更新注释信息.
-#
+#   20220920:更新inflation_layer配置参数.
 
-#单独圆形机器人的底盘半径参数
-robot_radius: 0.10
+#单独圆形机器人的底盘半径参数,不带前面夹爪
+#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.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]]
+
 map_type: costmap
 
+#障碍物图层
 obstacle_layer:
  enabled: true
  obstacle_range: 1.0
@@ -35,7 +36,8 @@ obstacle_layer:
  observation_sources: scan
  scan: {sensor_frame: lidar, data_type: LaserScan, topic: scan, marking: true, clearing: true}
 
+#膨胀图层
 inflation_layer:
  enabled: true
  cost_scaling_factor: 5
- inflation_radius: 0.28
+ inflation_radius: 0.40

+ 15 - 14
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -3,26 +3,27 @@
 #   当小于该值小车将无法响应小车的旋转命令.
 #   vy_samples:在y方向速度空间采样点数,对于差速驱动的小车y方向速度永远只有一个0.0m/s,
 #     所以该值最小要设置为1,不能设置为0;
+#   prune_plan:定义当机器人是否边沿着路径移动时,清除掉已经走过的路径规划;
 # Author: corvin
 # History:
 #   20200413:init this file.
 #   20220902:优化导航参数,使dwa算法运行更稳定;
-#
+#   20220920:优化dwa算法参数,使运行更稳定;
 
 base_local_planner: "dwa_local_planner/DWAPlannerROS"
 
 DWAPlannerROS:
 # Robot configuration params
-  acc_lim_x: 0.5
+  acc_lim_x: 0.7
   acc_lim_y: 0
-  acc_lim_th: 1.5
+  acc_lim_th: 1.8
 
-  max_vel_trans: 0.8
+  max_vel_trans: 0.7
   min_vel_trans: 0.1
   trans_stopped_vel: 0.1
 
-  max_vel_x: 0.8
-  min_vel_x: -0.8
+  max_vel_x: 0.7
+  min_vel_x: -0.7
 
   max_vel_y: 0
   min_vel_y: 0
@@ -32,22 +33,22 @@ DWAPlannerROS:
   theta_stopped_vel: 0.4
 
 # Goal Tolerance Parametes
-  xy_goal_tolerance: 0.25
-  yaw_goal_tolerance: 0.3
+  xy_goal_tolerance: 0.2
+  yaw_goal_tolerance: 0.2
   latch_xy_goal_tolerance: false
 
 # Forward Simulation Parametesrs
-  sim_time: 1
-  vx_samples: 5
+  sim_time: 1.7
+  vx_samples: 4
   vy_samples: 1
   vth_samples: 20
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 32.0
+  path_distance_bias: 40.0
   goal_distance_bias: 20.0
   occdist_scale: 0.02
-  forward_point_distance: 0.325
-  stop_time_buffer: 0.2
+  forward_point_distance: 0.2
+  stop_time_buffer: 0.4
   scaling_speed: 0.25
   max_scaling_factor: 0.2
 
@@ -55,4 +56,4 @@ DWAPlannerROS:
   oscillation_reset_dist: 0.05
 
 # Global plan parameters
-  prune_plan: true
+  prune_plan: true

+ 4 - 4
src/robot_navigation/config/global_costmap_params.yaml

@@ -1,5 +1,4 @@
-# Description:
-#   全局代价地图配置文件,各参数意义如下:
+# Description:全局代价地图的配置文件,各参数意义如下:
 #   global_frame: 全局代价地图参考系
 #   robot_base_frame: 指定机器人的基础参考系
 #   update_frequency: 指定地图更新频率,数值太大造成CPU负担重
@@ -11,19 +10,20 @@
 # History:
 #   20180410: init this file.
 #   20200927:增加plugins参数,配置静态层和膨胀层.
+
 global_costmap:
    global_frame: map
    robot_base_frame: base_footprint
 
    update_frequency: 1.0
    publish_frequency: 1.0
-   #static_map: true
+   static_map: true
    rolling_window: false
    resolution: 0.05
    transform_tolerance: 10.0
 
    plugins:
    - {name: static_layer,     type: "costmap_2d::StaticLayer"}
-   - {name: obstacle_layer,     type: "costmap_2d::VoxelLayer"}
+   - {name: obstacle_layer,   type: "costmap_2d::VoxelLayer"}
    - {name: inflation_layer,  type: "costmap_2d::InflationLayer"}
 

+ 7 - 8
src/robot_navigation/config/local_costmap_params.yaml

@@ -1,20 +1,19 @@
-#Description:
-#  本地代价地图配置文件,各参数意义如下:
+#Description: 本地代价地图配置文件,各参数意义如下:
 #  global_frame:指定本地代价地图参考系
 #  robot_base_frame:指定机器人的base_frame
 #  update_frequency:指定local代价地图更新频率
 #  publish_frequency: 代价地图发布可视化信息的频率
 #  static_map: 本地代价地图不会更新地图,设置false
 #  rolling_window: 设置滚动窗口,使机器人始终在窗体中心位置
-#  width: 代价地图宽度,滑动地图x维长度
-#  height:代价地图长度,滑动地图y维长度
-#  resolution: 代价地图的分辨率,该参数需要与yaml文件设置的地图
-#    分辨率匹配
+#  width: 局部代价地图宽度,滑动地图x维长度
+#  height:局部代价地图长度,滑动地图y维长度
+#  resolution: 代价地图的分辨率,该参数需要与yaml文件设置的地图分辨率匹配
 #Author: corvin
 #History:
 #  20180410: init this file.
 #  20200413:更新本地代价地图配置参数.
 #  20200927:添加plugins参数,配置障碍物层和膨胀层.
+
 local_costmap:
     global_frame: map
     robot_base_frame: base_footprint
@@ -23,8 +22,8 @@ local_costmap:
 
     #static_map: false
     rolling_window: true
-    width: 2.0
-    height: 2.0
+    width: 1.5
+    height: 1.5
     resolution: 0.05   #should same as map.yaml file
     transform_tolerance: 10.0
 

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

@@ -1,5 +1,5 @@
 <!--
-  Description:使用EAI的X2L雷达进行amcl定位,加载地图进行路径规划,自动导航
+  Description:使用EAI的X2L雷达进行amcl定位,加载地图进行自动导航,这里加载的局部路径规划算法是dwa.
   Author: corvin
   History:
     20200326:init this file.

BIN
src/robot_navigation/maps/test_map.pgm


+ 12 - 17
src/robot_navigation/rviz/view_navigation.rviz

@@ -6,7 +6,7 @@ Panels:
       Expanded:
         - /Odometry1/Shape1
       Splitter Ratio: 0.5083333253860474
-    Tree Height: 398
+    Tree Height: 311
   - Class: rviz/Selection
     Name: Selection
   - Class: rviz/Tool Properties
@@ -369,34 +369,29 @@ Visualization Manager:
   Value: true
   Views:
     Current:
-      Class: rviz/Orbit
-      Distance: 4.645807266235352
+      Angle: 0
+      Class: rviz/TopDownOrtho
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.05999999865889549
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
-      Focal Point:
-        X: 1.1761776208877563
-        Y: 0.12880270183086395
-        Z: 0.183502197265625
-      Focal Shape Fixed Size: true
-      Focal Shape Size: 0.05000000074505806
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.009999999776482582
-      Pitch: 1.5197967290878296
+      Scale: 121.00311279296875
       Target Frame: <Fixed Frame>
-      Value: Orbit (rviz)
-      Yaw: 4.673709392547607
+      Value: TopDownOrtho (rviz)
+      X: 2.0725924968719482
+      Y: 0.9657533764839172
     Saved: ~
 Window Geometry:
   Displays:
     collapsed: true
-  Height: 803
+  Height: 815
   Hide Left Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000251fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000004400000251000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004ab00000044fc0100000002fb0000000800540069006d00650100000000000004ab0000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ab0000027400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000251fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000004400000251000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000280fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000280000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650100000000000004d40000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004d40000028000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
@@ -405,6 +400,6 @@ Window Geometry:
     collapsed: false
   Views:
     collapsed: true
-  Width: 1195
-  X: 18
-  Y: 162
+  Width: 1236
+  X: 14
+  Y: 102