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=0ce322b1d25fd45cc313cccf30f7c46c5a1682cb;hb=d0c13eed893ea8d50dd8f6471af5a19c625d7842;hpb=670ead7985c1c4df661d9e95e20a0b805c0347f8 diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index 0ce322b..612ab55 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -14,19 +14,31 @@ TrajectoryPlannerROS: # 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: true + 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 @@ -40,3 +52,8 @@ DWAPlannerROS: 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