Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] authored and beyza committed Jun 20, 2023
1 parent 138da8f commit b2b25f3
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -1980,16 +1981,15 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
std::vector<lanelet::ConstLanelets> 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;

Expand Down

0 comments on commit b2b25f3

Please sign in to comment.