X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fbase_local_planner_params.yaml;h=5b3515dd4cb4dd426f2f17039c18d110f89e795c;hp=612ab552ad977c17ee1cbad56e7a5c98c142a8db;hb=5265263d46b9396252d852a763e68913ad3a913e;hpb=600928bc1ad74c0d227c414f6e9298cc8d66c959 diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index 612ab55..5b3515d 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -1,12 +1,13 @@ TrajectoryPlannerROS: - min_vel_x: 0.2 + 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: 10.07 + acc_lim_x: 0.14 acc_lim_y: 0.0 acc_lim_theta: 6.00 @@ -16,6 +17,8 @@ TrajectoryPlannerROS: 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 @@ -41,19 +44,50 @@ DWAPlannerROS: acc_lim_th: 6.00 max_vel_x: 0.5 - min_vel_x: 0.0 # no backward movement + min_vel_x: 0.1 max_vel_y: 0.0 min_vel_y: 0.0 max_trans_vel: 0.5 - min_trans_vel: 0.2 + min_trans_vel: 0.1 max_rot_vel: 1.0 min_rot_vel: 0.4 - xy_goal_tolerance: 0.1 - yaw_goal_tolerance: 0.2 + 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