]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/base_local_planner_params.yaml
Merge branch 'master' of ssh://vontaene/home/erik_alt/git/ros_wild_thumper
[ros_wild_thumper.git] / config / base_local_planner_params.yaml
index 3b509c3ee603f5605462b5a1dbc5891e2b7069ce..5b3515dd4cb4dd426f2f17039c18d110f89e795c 100644 (file)
@@ -1,13 +1,93 @@
 TrajectoryPlannerROS:
-  min_vel_x: 0.1
-  max_vel_x: 0.3
-  min_vel_theta: -0.4
-  max_vel_theta: 0.4
+  min_vel_x: 0.05
+  max_vel_x: 0.5
+  min_vel_theta: -1.0
+  max_vel_theta: 1.0
   min_in_place_vel_theta: 0.4
+  max_rotational_vel: 1.0 # used by rotate recovery
+  escape_vel: 0.0 # Speed used for driving during escapes in meters/sec. Will move slowly even when the static map shows it as blocked
 
-  acc_lim_x: 2.5
+  acc_lim_x: 0.14
   acc_lim_y: 0.0
-  acc_lim_theta: 0.3
+  acc_lim_theta: 6.00
 
   holonomic_robot: false
+  # gdist_scale and pdist_scale parameters should assume meters
   meter_scoring: true
+
+  xy_goal_tolerance: 0.15
+  yaw_goal_tolerance: 0.1
+  # If goal tolerance is latched, if the robot ever reaches the goal xy location it will simply rotate in place, even if it ends up outside the goal tolerance while it is doing so.
+  latch_xy_goal_tolerance: true
+
+  # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
+  occdist_scale: 0.02
+
+  # Whether to score based on the robot's heading to the path or its distance from the path, default: false
+  heading_scoring: false
+
+  # How far to look ahead in time in seconds along the simulated trajectory when using heading scoring, default: 0.1
+  heading_scoring_timestep: 0.3
+
+  # 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
+  acc_lim_th: 6.00
+
+  max_vel_x: 0.5
+  min_vel_x: 0.1
+  max_vel_y: 0.0
+  min_vel_y: 0.0
+
+  max_trans_vel: 0.5
+  min_trans_vel: 0.1
+  max_rot_vel: 1.0
+  min_rot_vel: 0.4
+
+  xy_goal_tolerance: 0.15
+  yaw_goal_tolerance: 0.1
+
+  # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
+  occdist_scale: 0.02
+  # The weighting for how much the controller should stay close to the path it was given, default: 32.0
+  path_distance_bias: 64.0
+
+PoseFollower:
+  holonomic: false
+  max_vel_lin: 0.5
+  max_vel_th: 1.0
+  min_vel_lin: 0.0
+  min_vel_th: 0.0
+  tolerance_trans: 0.15
+  tolerance_rot: 0.1
+  tolerance_timeout: 0.1
+  trans_stopped_velocity: 0.001
+  rot_stopped_velocity: 0.001
+  allow_backwards: false
+  # If true, turn in place to face the new goal instead of arching towards it
+  turn_in_place_first: false
+  # If turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location
+  max_heading_diff_before_moving: 0.175
+  # Gain factor for translation component of output velocities 0..20
+  k_trans: 1.0
+  # Gain factor for rotation component of output velocities: 0..20
+  k_rot: 2.0
+  collision_planner: # =TrajectoryPlannerROS
+    holonomic_robot: false
+    meter_scoring: true
+    xy_goal_tolerance: 0.15
+    yaw_goal_tolerance: 0.1
+    heading_scoring: false
+    heading_scoring_timestep: 0.3
+    oscillation_reset_dist: 0.1
+    sim_granularity: 0.05
+    angular_sim_granularity: 0.05