Browse Source

修改costmap参数使dwa能够动态避障

corvin_zhang 4 years ago
parent
commit
da27a08b00

+ 16 - 7
src/robot_navigation/config/costmap_common_params.yaml

@@ -17,8 +17,7 @@
 #   20180410:init this file.
 #   20200413:更新参数并更新注释信息.
 #
-obstacle_range: 1.0
-raytrace_range: 1.5
+
 
 #单独圆形机器人的参数
 #robot_radius: 0.13
@@ -28,11 +27,21 @@ 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]]
+map_type: costmap
+
+obstacle_layer:
+ enabled: true
+ obstacle_range: 1.0
+ raytrace_range: 1.5
+ inflation_radius: 0.05
+ observation_sources: scan
+ scan: {sensor_frame: lidar, data_type: LaserScan, topic: scan, marking: true, clearing: true}
+
+
+inflation_layer:
+ enabled: true
+ cost_scaling_factor: 10
+ inflation_radius:     0.10
 
-inflation_radius: 0.15
-cost_scaling_factor: 10
 
-map_type: costmap
-observation_sources: scan
-scan: {sensor_frame: lidar, data_type: LaserScan, topic: scan, marking: true, clearing: true}
 

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

@@ -31,7 +31,7 @@ DWAPlannerROS:
   latch_xy_goal_tolerance: false
 
 # Forward Simulation Parameters
-  sim_time: 1.5
+  sim_time: 2
   vx_samples: 10
   vy_samples: 10
   vth_samples: 40

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

@@ -14,7 +14,7 @@
 -->
 <launch>
   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
-    <param name="controller_frequency" value="4.5" />
+    <param name="controller_frequency" value="3.5" />
     <param name="controller_patiente"  value="3.0" />
 
     <param name="planner_patience"  value="5.0" />