Skip to content

Commit 047170a

Browse files
style(pre-commit): autofix
1 parent 1c3540a commit 047170a

File tree

2 files changed

+6
-9
lines changed

2 files changed

+6
-9
lines changed

planning/mission_planner/src/lanelet2_plugins/default_planner.cpp

+4-5
Original file line numberDiff line numberDiff line change
@@ -333,10 +333,8 @@ bool DefaultPlanner::is_goal_valid(
333333

334334
lanelet::ConstLanelet goal_lanelet;
335335
lanelet::ConstLanelets goal_lanelets;
336-
if (!lanelet::utils::query::getCurrentLanelets(
337-
road_lanelets_, goal, &goal_lanelets)) {
338-
if (!lanelet::utils::query::getClosestLanelet(
339-
road_lanelets_, goal, &goal_lanelet)) {
336+
if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, goal, &goal_lanelets)) {
337+
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &goal_lanelet)) {
340338
}
341339
goal_lanelets = {goal_lanelet};
342340
}
@@ -356,7 +354,8 @@ bool DefaultPlanner::is_goal_valid(
356354
for (const auto & gl_llt : goal_lanelets) {
357355
if (
358356
param_.check_footprint_inside_lanes &&
359-
!check_goal_footprint_inside_lanes(gl_llt, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
357+
!check_goal_footprint_inside_lanes(
358+
gl_llt, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
360359
!is_in_parking_lot(
361360
lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_),
362361
lanelet::utils::conversion::toLaneletPoint(goal.position))) {

planning/route_handler/src/route_handler.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -2142,10 +2142,8 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
21422142
// Find lanelets for goal point.
21432143
lanelet::ConstLanelet goal_lanelet;
21442144
lanelet::ConstLanelets goal_lanelets;
2145-
if (!lanelet::utils::query::getCurrentLanelets(
2146-
road_lanelets_, goal_checkpoint, &goal_lanelets)) {
2147-
if (!lanelet::utils::query::getClosestLanelet(
2148-
road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2145+
if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, goal_checkpoint, &goal_lanelets)) {
2146+
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_checkpoint, &goal_lanelet)) {
21492147
RCLCPP_WARN_STREAM(
21502148
logger_, "Failed to find current lanelet."
21512149
<< std::endl

0 commit comments

Comments
 (0)