diff --git a/common/autoware_trajectory/src/pose.cpp b/common/autoware_trajectory/src/pose.cpp index 14806bb4701ae..35eca81981f89 100644 --- a/common/autoware_trajectory/src/pose.cpp +++ b/common/autoware_trajectory/src/pose.cpp @@ -45,8 +45,8 @@ PointType Trajectory::compute(double s) const { PointType result; result.position = BaseClass::compute(s); - result.orientation = orientation_interpolator_->compute(s); s = clamp(s); + result.orientation = orientation_interpolator_->compute(s); return result; }