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] committed Sep 3, 2024
1 parent bd02220 commit 49babe6
Showing 1 changed file with 4 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -456,17 +456,16 @@ void BehaviorPathPlannerNode::run()
const auto current_pose = planner_data_->self_odometry->pose.pose;
double bound_to_centerline = 0.0;
const auto current_lanelets = planner_data_->route_handler->getRoadLaneletsAtPose(current_pose);
// const auto bidirectional_lanelets = getBidirectionalLanelets(current_lanelets.at(0));
// const auto bidirectional_lanelets = getBidirectionalLanelets(current_lanelets.at(0));
if (!path->points.empty()) {
const size_t current_seg_idx = planner_data_->findEgoSegmentIndex(path->points);
path->points = autoware::motion_utils::cropPoints(
path->points, current_pose.position, current_seg_idx,
planner_data_->parameters.forward_path_length,
planner_data_->parameters.backward_path_length +
planner_data_->parameters.input_path_interval);
if(planner_data_->parameters.check_bidirectional_lane){
if (planner_data_->parameters.check_bidirectional_lane) {
for (const auto & current_lanelet : current_lanelets) {

bound_to_centerline = lanelet::geometry::distance2d(
lanelet::utils::to2D(current_lanelet.leftBound().basicLineString()),
lanelet::utils::to2D(current_lanelet.centerline().basicLineString()));
Expand Down Expand Up @@ -551,8 +550,8 @@ void BehaviorPathPlannerNode::run()
return shifted_path;
}

[[maybe_unused]]LaneletsData BehaviorPathPlannerNode::getBidirectionalLanelets(
[[maybe_unused]]const lanelet::ConstLanelet & current_lanelet)
[[maybe_unused]] LaneletsData BehaviorPathPlannerNode::getBidirectionalLanelets(
[[maybe_unused]] const lanelet::ConstLanelet & current_lanelet)
{
LaneletsData bidirectional_lanelets;

Expand Down

0 comments on commit 49babe6

Please sign in to comment.