]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/base_local_planner_params.yaml
dwa planner tuning
[ros_wild_thumper.git] / config / base_local_planner_params.yaml
index 9cc7b79ad5bd8f469ba3ef372c65962648ab2651..bbd95c1c339522ef49e863a4ac614b52133d3062 100644 (file)
@@ -1,13 +1,35 @@
 TrajectoryPlannerROS:
-  min_vel_x: 0.1
+  min_vel_x: 0.2
   max_vel_x: 0.3
-  min_vel_theta: -1.0
-  max_vel_theta: 1.0
+  min_vel_theta: -0.4
+  max_vel_theta: 0.4
   min_in_place_vel_theta: 0.4
+  max_rotational_vel: 0.5 # used by rotate recovery
 
-  acc_lim_x: 2.5
+  acc_lim_x: 10.07
   acc_lim_y: 0.0
-  acc_lim_theta: 3.2
+  acc_lim_theta: 12.00
 
   holonomic_robot: false
   meter_scoring: true
+
+  xy_goal_tolerance: 0.20
+  yaw_goal_tolerance: 0.3
+
+DWAPlannerROS:
+  acc_lim_x: 10.07
+  acc_lim_y: 0.0
+  acc_lim_th: 12.00
+
+  max_vel_x: 0.5
+  min_vel_x: 0.0 # no backward movement
+  max_vel_y: 0.0
+  min_vel_y: 0.0
+
+  max_trans_vel: 0.5
+  min_trans_vel: 0.2
+  max_rot_vel: 0.5
+  min_rot_vel: 0.4
+
+  xy_goal_tolerance: 0.20
+  yaw_goal_tolerance: 0.3