X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fbase_local_planner_params.yaml;h=bbd95c1c339522ef49e863a4ac614b52133d3062;hp=212e2b639d5af79ed6938397e3c2d245385fc751;hb=3e7d2e6fd87ff390509020f73776417cea105d89;hpb=53c52f19f4cd243c9f5a66780ca365d54820761f diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index 212e2b6..bbd95c1 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -4,12 +4,32 @@ TrajectoryPlannerROS: min_vel_theta: -0.4 max_vel_theta: 0.4 min_in_place_vel_theta: 0.4 + max_rotational_vel: 0.5 # used by rotate recovery - acc_lim_x: 2.5 + acc_lim_x: 10.07 acc_lim_y: 0.0 - acc_lim_theta: 0.3 + acc_lim_theta: 12.00 holonomic_robot: false meter_scoring: true - sim_granularity: 0.01 + xy_goal_tolerance: 0.20 + yaw_goal_tolerance: 0.3 + +DWAPlannerROS: + acc_lim_x: 10.07 + acc_lim_y: 0.0 + acc_lim_th: 12.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: 0.5 + min_rot_vel: 0.4 + + xy_goal_tolerance: 0.20 + yaw_goal_tolerance: 0.3