Browse Source

优化move_base启动参数,增加dwa_local planner配置文件

corvin 5 years ago
parent
commit
a161bf9f74

+ 45 - 0
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -0,0 +1,45 @@
+DWAPlannerROS:
+
+#robot configuration params
+  acc_lim_x: 0.5
+  acc_lim_y: 0.5
+  acc_lim_th: 1.0
+
+  max_trans_vel: 0.3
+  min_trans_vel: 0.15
+
+  max_vel_x: 0.2
+  min_vel_x: -0.2
+
+  max_vel_y: 0.2
+  min_vel_y: -0.2
+
+  max_rot_vel: 2.0
+  min_rot_vel: 0.4
+
+# Goal Tolerance Parametes
+  xy_goal_tolerance: 0.10
+  yaw_goal_tolerance: 0.17
+  latch_xy_goal_tolerance: false
+
+# Forward Simulation Parameters
+  sim_time: 1.5
+  vx_samples: 10
+  vy_samples: 10
+  vth_samples: 40
+  controller_frequency: 4.0
+
+# Trajectory Scoring Parameters
+  path_distance_bias: 32.0
+  goal_distance_bias: 20.0
+  occdist_scale: 0.02
+  forward_point_distance: 0.325
+  stop_time_buffer: 0.2
+  scaling_speed: 0.25
+  max_scaling_factor: 0.2
+
+# Oscillation Prevention Parameters
+  oscillation_reset_dist: 0.05
+
+# Global plan parameters
+  prune_plan: true

+ 17 - 3
src/robot_navigation/launch/move_base.launch

@@ -13,16 +13,30 @@
 -->
 <launch>
   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
+    <param name="base_global_planner" value="navfn/NavfnROS" />
+    <param name="base_local_planner"  value="dwa_local_planner/DWAPlannerROS" />
+
     <param name="controller_frequency" value="4" />
     <param name="controller_patiente"  value="10" />
 
+    <param name="planner_patience"  value="5.0" />
+    <param name="planner_frequency" value="1.0" />
+    <param name="conservative_reset_dist" value="3.0" />
+
+    <param name="recovery_behavior_enabled" value="true" />
+    <param name="clearing_rotation_allowed" value="true" />
+
+    <param name="shutdown_costmaps"    value="false" />
+    <param name="oscillation_timeout"  value="10.0" />
+    <param name="oscillation_distance" value="0.2" />
+
+    <param name="max_planning_retries" value="10"  />
+
     <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" />
     <rosparam file="$(find robot_navigation)/config/local_costmap_params.yaml"  command="load" />
     <rosparam file="$(find robot_navigation)/config/global_costmap_params.yaml" command="load" />
-    <rosparam file="$(find robot_navigation)/config/base_local_planner_params.yaml" command="load" />
-
-    <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
+    <rosparam file="$(find robot_navigation)/config/dwa_local_planner_params.yaml" command="load" />
   </node>
 </launch>