From 924614673d198b7d38cc264ec512ee8c1b0bb6a7 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 27 Jan 2025 10:25:16 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../src/metrics/trajectory_metrics.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp index 61a888971d5fb..d08685567f12b 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp @@ -86,12 +86,13 @@ Accumulator calcTrajectoryResampledRelativeAngle( Accumulator stat; const auto resample_offset = vehicle_length_m / 2; - const auto arc_length = autoware::motion_utils::calcSignedArcLengthPartialSum(traj.points, 0, traj.points.size()); + const auto arc_length = + autoware::motion_utils::calcSignedArcLengthPartialSum(traj.points, 0, traj.points.size()); for (size_t base_id = 0; base_id < arc_length.size() - 1; ++base_id) { // Get base pose yaw const double base_yaw = tf2::getYaw(traj.points.at(base_id).pose.orientation); - for (size_t i = base_id; i < arc_length.size() -1; ++i) { + for (size_t i = base_id; i < arc_length.size() - 1; ++i) { if (arc_length[i] >= arc_length[base_id] + resample_offset) { // Get target pose yaw const double target_yaw = tf2::getYaw(traj.points.at(i).pose.orientation); @@ -106,7 +107,6 @@ Accumulator calcTrajectoryResampledRelativeAngle( return stat; } - Accumulator calcTrajectoryCurvature(const Trajectory & traj) { Accumulator stat;