Skip to content

Commit

Permalink
Reduced curvature threshold and backward trajectory length
Browse files Browse the repository at this point in the history
  • Loading branch information
sadheedhumar committed Dec 13, 2024
1 parent a02dfbc commit c8406af
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,9 @@
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]
# steering angle rate limit parameters
enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime.
max_steering_angle_rate: 10.0 # maximum steering angle rate [degree/s]
#reduced it to be within the planning validators limit, or it will trip off the validator.
max_steering_angle_rate: 10.0 # maximum steering angle rate [degree/s] #SJ default 11.5 #reduced it to be within the planning validators limit, or it will trip off the validator.
resample_ds: 0.1 # distance between trajectory points [m]
curvature_threshold: 0.05 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] #SJ default 0.02 #The default curvature threshold value in the start planner shft pullout is 0.07. Might get in the way of that.
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] #SJ default 0.02 #The default curvature threshold value in the start planner shft pullout is 0.07. Might get in the way of that.

# engage & replan parameters
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
common:
# output
output_delta_arc_length: 0.5 # delta arc length for output trajectory [m]
output_backward_traj_length: 2.5 # backward length for backward trajectory from base_link [m] #SJ default 5.0 #IMPORTANT change - The higher the value, the larger the arc length of the smoothed out curve.
output_backward_traj_length: 1.0 # backward length for backward trajectory from base_link [m] #SJ default 5.0 #IMPORTANT change - The higher the value, the larger the arc length of the smoothed out curve.
# Higher values mean any maneuvers will have a much smoother and shallower curve. Lower values mean the curve arc length is smaller and can have a smaller radius.

vehicle_stop_margin_outside_drivable_area: 0.0 # vehicle stop margin to let the vehicle stop before the calculated stop point if it is calculated outside the drivable area [m] .
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
common:
# output
output_delta_arc_length: 0.5 # delta arc length for output trajectory [m]
output_backward_traj_length: 2.5 # backward length for backward trajectory from base_link [m] #SJ default 5.0 #IMPORTANT change - The higher the value, the larger the arc length of the smoothed out curve.
output_backward_traj_length: 1.0 # backward length for backward trajectory from base_link [m] #SJ default 5.0 #IMPORTANT change - The higher the value, the larger the arc length of the smoothed out curve.
# Higher values mean any maneuvers will have a much smoother and shallower curve. Lower values mean the curve arc length is smaller and can have a smaller radius.
# elastic band
elastic_band:
Expand Down

0 comments on commit c8406af

Please sign in to comment.