Skip to content

Commit c8336ed

Browse files
committed
fix(planning_validator): calculate max lateral acceleration after resampling trajectory (autowarefoundation#6679)
fix planning validator calc max lat acc after resampling Signed-off-by: kaigohirao <kaigo.hirao@proxima-ai-tech.com>
1 parent 3fa29a5 commit c8336ed

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

planning/planning_validator/src/planning_validator.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -247,7 +247,6 @@ void PlanningValidator::validate(const Trajectory & trajectory)
247247

248248
s.is_valid_finite_value = checkValidFiniteValue(trajectory);
249249
s.is_valid_interval = checkValidInterval(trajectory);
250-
s.is_valid_lateral_acc = checkValidLateralAcceleration(trajectory);
251250
s.is_valid_longitudinal_max_acc = checkValidMaxLongitudinalAcceleration(trajectory);
252251
s.is_valid_longitudinal_min_acc = checkValidMinLongitudinalAcceleration(trajectory);
253252
s.is_valid_velocity_deviation = checkValidVelocityDeviation(trajectory);
@@ -260,6 +259,7 @@ void PlanningValidator::validate(const Trajectory & trajectory)
260259

261260
s.is_valid_relative_angle = checkValidRelativeAngle(resampled);
262261
s.is_valid_curvature = checkValidCurvature(resampled);
262+
s.is_valid_lateral_acc = checkValidLateralAcceleration(resampled);
263263
s.is_valid_steering = checkValidSteering(resampled);
264264
s.is_valid_steering_rate = checkValidSteeringRate(resampled);
265265

0 commit comments

Comments
 (0)