X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fbase_local_planner_params.yaml;h=bc544b8b5b38f947fe3ed4336cec678194a7ea95;hp=eaff7f433397599401b61f7c46515acb27864491;hb=5d2b909797fd168b0981af8f4570d608a9a32626;hpb=3708a6b10b4b3b98e1c3422f545dba82948fec5a diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index eaff7f4..bc544b8 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -1,15 +1,59 @@ 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.2 + 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 - 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 - sim_granularity: 0.01 + 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 + + # 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.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: 1.0 + min_rot_vel: 0.4 + + xy_goal_tolerance: 0.1 + yaw_goal_tolerance: 0.2 + + # 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