Skip to content

Commit 23c6f54

Browse files
pre-commit-ci[bot]StepTurtle
authored andcommitted
style(pre-commit): autofix
1 parent 892e435 commit 23c6f54

File tree

1 file changed

+11
-10
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils

1 file changed

+11
-10
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp

+11-10
Original file line numberDiff line numberDiff line change
@@ -506,7 +506,8 @@ bool isEgoOutOfRoute(
506506

507507
bool is_failed_getting_lanelet;
508508
if (!common_param.enable_differential_map_loading) {
509-
is_failed_getting_lanelet = shoulder_goal_lanes.empty() && !route_handler->getGoalLanelet(&goal_lane);
509+
is_failed_getting_lanelet =
510+
shoulder_goal_lanes.empty() && !route_handler->getGoalLanelet(&goal_lane);
510511
} else {
511512
// If dynamic map is enabled, get the goal lanelet from the current lanelet map
512513
//
@@ -518,18 +519,18 @@ bool isEgoOutOfRoute(
518519
lanelet::ConstLanelets route_lanelets = route_handler->getRouteLanelets();
519520

520521
auto goalLaneletIt =
521-
std::find_if(all_lanelets.rbegin(), all_lanelets.rend(), [&](const auto & currentLanelet) {
522-
return currentLanelet.id() == route_lanelets.back().id();
523-
});
522+
std::find_if(all_lanelets.rbegin(), all_lanelets.rend(), [&](const auto & currentLanelet) {
523+
return currentLanelet.id() == route_lanelets.back().id();
524+
});
524525

525526
if (goalLaneletIt != all_lanelets.rend()) {
526-
RCLCPP_DEBUG(
527-
rclcpp::get_logger("behavior_path_planner").get_child("util"),
528-
"Found goal lanelet in current lanelet map");
529-
goal_lane = *goalLaneletIt;
530-
is_failed_getting_lanelet = false;
527+
RCLCPP_DEBUG(
528+
rclcpp::get_logger("behavior_path_planner").get_child("util"),
529+
"Found goal lanelet in current lanelet map");
530+
goal_lane = *goalLaneletIt;
531+
is_failed_getting_lanelet = false;
531532
}
532-
is_failed_getting_lanelet = !route_handler->getGoalLanelet(&goal_lane);
533+
is_failed_getting_lanelet = !route_handler->getGoalLanelet(&goal_lane);
533534
}
534535

535536
if (is_failed_getting_lanelet) {

0 commit comments

Comments
 (0)