From fc6a81c30e0797471bcc8b68f1bf63a5b805e4fb Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 22 Apr 2024 04:30:02 +0000 Subject: [PATCH] style(pre-commit): autofix --- planning/route_handler/src/route_handler.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index b63f42794af02..23e810d2e0aa9 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2267,7 +2267,7 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose lanelet::ConstLanelet current_lanelet; getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); - + lanelet::ConstLanelet goal_lanelet; getGoalLanelet(&goal_lanelet); @@ -2278,20 +2278,18 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose remaining_shortest_path = optional_route->shortestPath(); for (auto & llt : remaining_shortest_path) { - if (remaining_shortest_path.size() == 1) { - remaining_distance += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); + remaining_distance += + tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); break; } if (index == 0) { - lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates({llt}, current_pose); + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_pose); double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); remaining_distance += this_lanelet_length - arc_coord.length; } else if (index == (remaining_shortest_path.size() - 1)) { - lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates({llt}, goal_pose_); + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); remaining_distance += arc_coord.length; } else { remaining_distance += lanelet::utils::getLaneletLength2d(llt);