Skip to content

Commit 1600450

Browse files
style(pre-commit): autofix
1 parent 7f1702f commit 1600450

File tree

1 file changed

+5
-7
lines changed

1 file changed

+5
-7
lines changed

planning/route_handler/src/route_handler.cpp

+5-7
Original file line numberDiff line numberDiff line change
@@ -2267,7 +2267,7 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose
22672267

22682268
lanelet::ConstLanelet current_lanelet;
22692269
getClosestLaneletWithinRoute(current_pose, &current_lanelet);
2270-
2270+
22712271
lanelet::ConstLanelet goal_lanelet;
22722272
getGoalLanelet(&goal_lanelet);
22732273

@@ -2278,20 +2278,18 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose
22782278
remaining_shortest_path = optional_route->shortestPath();
22792279

22802280
for (auto & llt : remaining_shortest_path) {
2281-
22822281
if (remaining_shortest_path.size() == 1) {
2283-
remaining_distance += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position);
2282+
remaining_distance +=
2283+
tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position);
22842284
break;
22852285
}
22862286

22872287
if (index == 0) {
2288-
lanelet::ArcCoordinates arc_coord =
2289-
lanelet::utils::getArcCoordinates({llt}, current_pose);
2288+
lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_pose);
22902289
double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt);
22912290
remaining_distance += this_lanelet_length - arc_coord.length;
22922291
} else if (index == (remaining_shortest_path.size() - 1)) {
2293-
lanelet::ArcCoordinates arc_coord =
2294-
lanelet::utils::getArcCoordinates({llt}, goal_pose_);
2292+
lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_);
22952293
remaining_distance += arc_coord.length;
22962294
} else {
22972295
remaining_distance += lanelet::utils::getLaneletLength2d(llt);

0 commit comments

Comments
 (0)