From 76aa83fcd1a716692789fdc50fed6369c154cb43 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Fri, 10 Jan 2025 17:35:41 +0900 Subject: [PATCH] fix(planning_evaluator): update lateral_trajectory_displacement to absolute value (#9696) * fix(planning_evaluator): update lateral_trajectory_displacement to absolute value Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix --------- Signed-off-by: Kasunori-Nakajima Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/metrics/deviation_metrics.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index 82ba86c65d6af..9b5959948f8cb 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -58,7 +58,8 @@ Accumulator calcLocalLateralTrajectoryDisplacement( autoware::motion_utils::calcLateralOffset(prev.points, ego_pose.position); const auto traj_lateral_deviation = autoware::motion_utils::calcLateralOffset(traj.points, ego_pose.position); - const auto lateral_trajectory_displacement = traj_lateral_deviation - prev_lateral_deviation; + const auto lateral_trajectory_displacement = + std::abs(traj_lateral_deviation - prev_lateral_deviation); stat.add(lateral_trajectory_displacement); return stat; }