Skip to content

Commit

Permalink
fix(planning_validator): calculate max lateral acceleration after res…
Browse files Browse the repository at this point in the history
…ampling trajectory (autowarefoundation#6679)

fix planning validator calc max lat acc after resampling

Signed-off-by: kaigohirao <[email protected]>
  • Loading branch information
kaigohirao authored and TomohitoAndo committed Mar 27, 2024
1 parent e3f213e commit cfbda5e
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion planning/planning_validator/src/planning_validator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,6 @@ void PlanningValidator::validate(const Trajectory & trajectory)

s.is_valid_finite_value = checkValidFiniteValue(trajectory);
s.is_valid_interval = checkValidInterval(trajectory);
s.is_valid_lateral_acc = checkValidLateralAcceleration(trajectory);
s.is_valid_longitudinal_max_acc = checkValidMaxLongitudinalAcceleration(trajectory);
s.is_valid_longitudinal_min_acc = checkValidMinLongitudinalAcceleration(trajectory);
s.is_valid_velocity_deviation = checkValidVelocityDeviation(trajectory);
Expand All @@ -273,6 +272,7 @@ void PlanningValidator::validate(const Trajectory & trajectory)

s.is_valid_relative_angle = checkValidRelativeAngle(resampled);
s.is_valid_curvature = checkValidCurvature(resampled);
s.is_valid_lateral_acc = checkValidLateralAcceleration(resampled);
s.is_valid_steering = checkValidSteering(resampled);
s.is_valid_steering_rate = checkValidSteeringRate(resampled);

Expand Down

0 comments on commit cfbda5e

Please sign in to comment.