X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fbase_local_planner_params.yaml;h=612ab552ad977c17ee1cbad56e7a5c98c142a8db;hp=93b53a46a351200ad32737b7b83acccab75c315b;hb=78385af76591e5fa2c228f7e53c3b7f2fc2092d6;hpb=0bf5df6648a8d2ad791e2c0f95b83524eaded03a diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index 93b53a4..612ab55 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -1,24 +1,44 @@ TrajectoryPlannerROS: min_vel_x: 0.2 - max_vel_x: 0.3 - min_vel_theta: -0.4 - max_vel_theta: 0.4 + 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: 10.07 acc_lim_y: 0.0 - acc_lim_theta: 12.00 + acc_lim_theta: 6.00 holonomic_robot: false + # gdist_scale and pdist_scale parameters should assume meters meter_scoring: true - xy_goal_tolerance: 0.20 - yaw_goal_tolerance: 0.3 + 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: 12.00 + acc_lim_th: 6.00 max_vel_x: 0.5 min_vel_x: 0.0 # no backward movement @@ -27,8 +47,13 @@ DWAPlannerROS: max_trans_vel: 0.5 min_trans_vel: 0.2 - max_rot_vel: 0.4 - min_rot_vel: 0.3 + max_rot_vel: 1.0 + min_rot_vel: 0.4 + + xy_goal_tolerance: 0.1 + yaw_goal_tolerance: 0.2 - xy_goal_tolerance: 0.20 - yaw_goal_tolerance: 0.3 + # 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