Browse Source

更新costmap和dwa参数

corvin_zhang 5 years ago
parent
commit
b13a5e3fc1

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

@@ -20,14 +20,14 @@
 obstacle_range: 1.0
 raytrace_range: 1.5
 
-#圆形机器人的参数
-#robot_radius: 0.175
+#单独圆形机器人的参数
+#robot_radius: 0.13
 
 #圆形机器人前面带上下移动夹爪的参数
-footprint: [[ 0.00,  0.22],[-0.04,  0.22],[-0.04,  0.10],
-            [-0.71,  0.71],[-0.10,  0.00],[-0.71, -0.71],
-            [ 0.00, -0.10],[ 0.71, -0.71],[ 0.10,  0.00],
-            [ 0.71,  0.71],[ 0.04,  0.10],[ 0.04,  0.22]]
+footprint: [[ 0.22,  0.00],[ 0.22,  0.04],[ 0.10,  0.04],
+            [ 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.04],[ 0.22, -0.04]]
 
 inflation_radius: 0.15
 cost_scaling_factor: 10

+ 22 - 13
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -1,42 +1,51 @@
+# Copyright: 2016-2020 www.corvin.cn ROS小课堂
+# Description:DWA局部规划器配置参数
+# Author: corvin
+# History:
+#   20200413:init this file.
+#
 DWAPlannerROS:
 
 #robot configuration params
-  acc_lim_x: 0.5
-  acc_lim_y: 0.5
-  acc_lim_th: 1.0
+  acc_lim_x: 0.1
+  acc_lim_y: 0.1
+  acc_lim_th: 0.2
 
   max_vel_trans: 0.3
   min_vel_trans: 0.15
 
   max_vel_x: 0.2
-  min_vel_x: -0.2
+  min_vel_x: -0.16
 
   max_vel_y: 0.2
   min_vel_y: -0.2
 
-  max_vel_theta: 2.0
+# angular volocity limit
+  max_vel_theta: 0.8
   min_vel_theta: 0.4
+  min_in_place_vel_theta: 0.5
 
 # Goal Tolerance Parametes
   xy_goal_tolerance: 0.10
-  yaw_goal_tolerance: 0.17
+  yaw_goal_tolerance: 0.15
   latch_xy_goal_tolerance: false
 
 # Forward Simulation Parameters
-  sim_time: 1.5
-  vx_samples: 10
+  sim_time: 2.5
+  sim_granularity: 0.025
+  vx_samples: 15
   vy_samples: 10
-  vth_samples: 40
-  controller_frequency: 4.0
+  vth_samples: 30
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 32.0
-  goal_distance_bias: 20.0
+  path_distance_bias: 30.0
+  goal_distance_bias: 24.0
   occdist_scale: 0.02
   forward_point_distance: 0.325
   stop_time_buffer: 0.2
-  scaling_speed: 0.25
+  scaling_speed: 0.20
   max_scaling_factor: 0.2
+  publish_cost_grid: false
 
 # Oscillation Prevention Parameters
   oscillation_reset_dist: 0.05

+ 17 - 14
src/robot_navigation/config/global_costmap_params.yaml

@@ -1,18 +1,17 @@
-#Copyright(C): 2016-2018 ROS小课堂
-#Author: www.corvin.cn
-#Description:
-#  全局代价地图配置文件,各参数意义如下:
-#  global_frame: 全局代价地图参考系
-#  robot_base_frame: 指定机器人的基础参考系
-#  update_frequency: 指定地图更新频率,数值太大造成CPU负担重
-#  publish_frequency: 对于静态全局地图来说,不需不断发布
-#  static_map: 全局地图通常是静态的,因此设置为true
-#  rolling_window: 全局地图不会在机器人移动时候更新
-#  transform_tolerance: 指定在tf树中frame直接的转换最大延时,单位秒
-#History:
-#  20180410: init this file.
+# Copyright(C): 2016-2020 www.corvin.cn ROS小课堂
+# Description:
+#   全局代价地图配置文件,各参数意义如下:
+#   global_frame: 全局代价地图参考系
+#   robot_base_frame: 指定机器人的基础参考系
+#   update_frequency: 指定地图更新频率,数值太大造成CPU负担重
+#   publish_frequency: 对于静态全局地图来说,不需不断发布
+#   static_map: 全局地图通常是静态的,因此设置为true
+#   rolling_window: 全局地图不会在机器人移动时候更新
+#   transform_tolerance: 指定在tf树中frame直接的转换最大延时,单位秒
+# Author: corvin
+# History:
+#   20180410: init this file.
 #
-
 global_costmap:
    global_frame: map
    robot_base_frame: base_footprint
@@ -22,3 +21,7 @@ global_costmap:
    rolling_window: false
    transform_tolerance: 2.0
 
+   plugins:
+       - {name: static_map, type: "costmap_2d::StaticLayer"}
+       - {name: obstacles,  type: "costmap_2d::VoxelLayer"}
+

+ 16 - 13
src/robot_navigation/config/local_costmap_params.yaml

@@ -1,8 +1,7 @@
 #Copyright(c):2016-2020 www.corvin.cn ROS小课堂
-#Author: corvin
 #Description:
 #  本地代价地图配置文件,各参数意义如下:
-#  global_frame:指定本地代价地图参考系为odom
+#  global_frame:指定本地代价地图参考系
 #  robot_base_frame:指定机器人的base_frame
 #  update_frequency:指定local代价地图更新频率
 #  publish_frequency: 代价地图发布可视化信息的频率
@@ -12,19 +11,23 @@
 #  height:代价地图长度,滑动地图y维长度
 #  resolution: 代价地图的分辨率,该参数需要与yaml文件设置的地图
 #    分辨率匹配
+#Author: corvin
 #History:
 #  20180410: init this file.
-#
+#  20200413:更新本地代价地图配置参数.
 local_costmap:
-   global_frame: odom_combined
-   robot_base_frame: base_footprint
-   update_frequency: 1.0
-   publish_frequency: 1.0
+    plugins:
+        - {name: static_map,    type: "costmap_2d::StaticLayer"}
+        - {name: obstacles,     type: "costmap_2d::VoxelLayer"}
+    global_frame: odom_combined
+    robot_base_frame: base_footprint
+    update_frequency: 1.0
+    publish_frequency: 1.0
 
-   static_map: false
-   rolling_window: true
-   width: 2.0
-   height: 2.0
-   resolution: 0.02   #should same as map.yaml file
-   transform_tolerance: 2.0
+    static_map: false
+    rolling_window: true
+    width: 1.0
+    height: 1.0
+    resolution: 0.02   #should same as map.yaml file
+    transform_tolerance: 2.0
 

File diff suppressed because it is too large
+ 1 - 1
src/robot_navigation/maps/mymap.pgm


+ 1 - 1
src/robot_navigation/maps/mymap.yaml

@@ -1,6 +1,6 @@
 image: mymap.pgm
 resolution: 0.020000
-origin: [-5.000000, -5.000000, 0.000000]
+origin: [-15.240000, -5.000000, 0.000000]
 negate: 0
 occupied_thresh: 0.65
 free_thresh: 0.196

Some files were not shown because too many files changed in this diff