From b2b25f3564e25725461115d887d91fe579ce3c8b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 19 Jun 2023 21:28:18 +0000 Subject: [PATCH] style(pre-commit): autofix --- planning/route_handler/src/route_handler.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index f5af0cd2611a5..b67cb7443d35d 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1968,7 +1968,8 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( lanelet::ConstLanelets * path_lanelets) const { lanelet::ConstLanelets start_lanelets; - if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, start_checkpoint, &start_lanelets)) { + if (!lanelet::utils::query::getCurrentLanelets( + road_lanelets_, start_checkpoint, &start_lanelets)) { return false; } lanelet::Lanelet goal_lanelet; @@ -1980,16 +1981,15 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( std::vector candidate_paths; bool is_route_found = false; for (const auto & start_lanelet : start_lanelets) { - optional_route = - routing_graph_ptr_->getRoute(start_lanelet, goal_lanelet, 0); + optional_route = routing_graph_ptr_->getRoute(start_lanelet, goal_lanelet, 0); if (!optional_route) { RCLCPP_ERROR_STREAM( logger_, "Failed to find a proper path!" << std::endl << "start checkpoint: " << toString(start_checkpoint) << std::endl << "goal checkpoint: " << toString(goal_checkpoint) << std::endl - << "start lane id: " << start_lanelet.id() << std::endl - << "goal lane id: " << goal_lanelet.id() << std::endl); + << "start lane id: " << start_lanelet.id() << std::endl + << "goal lane id: " << goal_lanelet.id() << std::endl); } else { is_route_found = true;