Bladeren bron

更新costmap_common_params.yaml中膨胀层cost_scaling_factor参数5->15,使规划的全局路径更安全,不撞挡板

corvin rasp melodic 2 jaren geleden
bovenliggende
commit
6f7dcb4c84

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

@@ -22,13 +22,13 @@ GlobalPlanner:
     old_navfn_behavior: false
     lethal_cost: 253
     neutral_cost: 50
-    cost_factor: 3
+    cost_factor: 10
 
     #debug param
     publish_potential: false
     visualize_potential: false
 
     orientation_mode: 1
-    orientation_window_size: 1
+    orientation_window_size: 2
 
     outline_map: true

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

@@ -42,5 +42,5 @@ obstacle_layer:
 #膨胀图层
 inflation_layer:
  enabled: true
- cost_scaling_factor: 5
+ cost_scaling_factor: 15
  inflation_radius: 0.40

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

@@ -22,10 +22,10 @@
     <param name="clearing_rotation_allowed" value="true"/>
 
     <param name="shutdown_costmaps"    value="false"/>
-    <param name="oscillation_timeout"  value="10.0"/>
+    <param name="oscillation_timeout"  value="5.0"/>
     <param name="oscillation_distance" value="0.2"/>
 
-    <param name="max_planning_retries" value="10"/>
+    <param name="max_planning_retries" value="5"/>
 
     <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
     <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap"/>

BIN
src/robot_navigation/maps/test_map.pgm