Skip to content

Commit

Permalink
ci(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jun 22, 2022
1 parent 55bd202 commit 5dddb44
Show file tree
Hide file tree
Showing 5 changed files with 9 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,7 @@ lanelet::ConstLanelets calcLaneAroundPose(
lanelet::ConstLanelet current_lane;
if (!route_handler->getClosestLaneletWithinRoute(pose, &current_lane)) {
RCLCPP_ERROR_THROTTLE(
rclcpp::getLogger("behavior_path_planner").get_child("avoidance"),
*get_clock(),
5000,
rclcpp::getLogger("behavior_path_planner").get_child("avoidance"), *get_clock(), 5000,
"failed to find closest lanelet within route!!!");
return {}; // TODO(Horibe)
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,8 @@ lanelet::ConstLanelets LaneChangeModule::getCurrentLanes() const

lanelet::ConstLanelet current_lane;
if (!route_handler->getClosestLaneletWithinRoute(current_pose, &current_lane)) {
RCLCPP_ERROR_THROTTLE(getLogger(), *get_clock(), 5000, "failed to find closest lanelet within route!!!");
RCLCPP_ERROR_THROTTLE(
getLogger(), *get_clock(), 5000, "failed to find closest lanelet within route!!!");
return {}; // TODO(Horibe) what should be returned?
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,8 @@ PathWithLaneId LaneFollowingModule::getReferencePath() const

lanelet::ConstLanelet current_lane;
if (!planner_data_->route_handler->getClosestLaneletWithinRoute(current_pose, &current_lane)) {
RCLCPP_ERROR_THROTTLE(getLogger(), *get_clock(), 5000, "failed to find closest lanelet within route!!!");
RCLCPP_ERROR_THROTTLE(
getLogger(), *get_clock(), 5000, "failed to find closest lanelet within route!!!");
return reference_path; // TODO(Horibe)
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,8 @@ lanelet::ConstLanelets PullOverModule::getCurrentLanes() const

lanelet::ConstLanelet current_lane;
if (!route_handler->getClosestLaneletWithinRoute(current_pose, &current_lane)) {
RCLCPP_ERROR_THROTTLE(getLogger(), clock, 5000, "failed to find closest lanelet within route!!!");
RCLCPP_ERROR_THROTTLE(
getLogger(), clock, 5000, "failed to find closest lanelet within route!!!");
return {}; // TODO(Horibe) what should be returned?
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,8 @@ void SideShiftModule::updateData()

lanelet::ConstLanelet current_lane;
if (!route_handler->getClosestLaneletWithinRoute(reference_pose.pose, &current_lane)) {
RCLCPP_ERROR_THROTTLE(getLogger(), *get_clock(), 5000, "failed to find closest lanelet within route!!!");
RCLCPP_ERROR_THROTTLE(
getLogger(), *get_clock(), 5000, "failed to find closest lanelet within route!!!");
}

// For current_lanes with desired length
Expand Down

0 comments on commit 5dddb44

Please sign in to comment.