]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/base_local_planner_params.yaml
Added rtl_sdr_strength.py
[ros_wild_thumper.git] / config / base_local_planner_params.yaml
index b163e5e1e649c8e14cc591ce1c8852566d7df1f0..bc544b8b5b38f947fe3ed4336cec678194a7ea95 100644 (file)
@@ -6,7 +6,7 @@ TrajectoryPlannerROS:
   min_in_place_vel_theta: 0.4
   max_rotational_vel: 1.0 # used by rotate recovery
 
-  acc_lim_x: 10.07
+  acc_lim_x: 0.14
   acc_lim_y: 0.0
   acc_lim_theta: 6.00
 
@@ -29,6 +29,12 @@ TrajectoryPlannerROS:
   # How far the robot must travel in meters before oscillation flags are reset, default: 0.05
   oscillation_reset_dist: 0.1
 
+  # The step size, in meters, to take between points on a given trajectory, default: 0.025
+  sim_granularity: 0.05
+
+  # The step size, in radians, to take between angular samples on a given trajectory, default: sim_granularity
+  angular_sim_granularity: 0.05
+
 DWAPlannerROS:
   acc_lim_x: 10.07
   acc_lim_y: 0.0