Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_behavior_path_planner): shift path according to traffic flow in bidirectional lanes #8672

Draft
wants to merge 1 commit into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
turn_signal_shift_length_threshold: 0.3
turn_signal_remaining_shift_length_threshold: 0.1
turn_signal_on_swerving: true
check_bidirectional_lane: true
traffic_flow: "left_side" # right or left

enable_akima_spline_first: false
enable_cog_on_centerline: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -235,6 +235,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
const std::shared_ptr<PathWithLaneId> & path_candidate_ptr, const bool is_ready,
const std::shared_ptr<PlannerData> & planner_data);

PathWithLaneId shiftPath(const PathWithLaneId & ref_paths, const double shift_distance);
bool isLaneBidirectional(const lanelet::ConstLanelets & current_lanelets);
std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;

std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021-2023 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.25 to 5.36, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -383,14 +383,29 @@
// NOTE: In order to keep backward_path_length at least, resampling interval is added to the
// backward.
const auto current_pose = planner_data_->self_odometry->pose.pose;

const auto current_lanelets = planner_data_->route_handler->getRoadLaneletsAtPose(current_pose);
const auto is_bidirectional = isLaneBidirectional(current_lanelets);
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 && is_bidirectional) {
double bound_to_centerline = 0.0;
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()));
}
if (planner_data_->parameters.traffic_flow == "right_side") {
path->points = shiftPath(*path, bound_to_centerline * 0.5).points;
} else if (planner_data_->parameters.traffic_flow == "left_side") {
path->points = shiftPath(*path, -bound_to_centerline * 0.5).points;
}
}

Check warning on line 408 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

BehaviorPathPlannerNode::run increases in cyclomatic complexity from 18 to 23, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
if (!path->points.empty()) {
path_publisher_->publish(*path);
published_time_publisher_->publish_if_subscribed(path_publisher_, path->header.stamp);
Expand Down Expand Up @@ -434,6 +449,55 @@
RCLCPP_DEBUG(get_logger(), "----- behavior path planner end -----\n\n");
}

PathWithLaneId BehaviorPathPlannerNode::shiftPath(

Check warning on line 452 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp#L452

Added line #L452 was not covered by tests
const PathWithLaneId & path, const double shift_distance)
{
PathWithLaneId shifted_path;
shifted_path.header.stamp = path.header.stamp;

Check warning on line 456 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp#L456

Added line #L456 was not covered by tests
shifted_path.points.reserve(path.points.size());
for (const auto & pose : path.points) {
tier4_planning_msgs::msg::PathPointWithLaneId shifted_pose{};
shifted_pose = pose;
// Get yaw from quaternion
tf2::Quaternion quat(
pose.point.pose.orientation.x, pose.point.pose.orientation.y, pose.point.pose.orientation.z,
pose.point.pose.orientation.w);
tf2::Matrix3x3 mat(quat);
double roll, pitch, yaw;
mat.getRPY(roll, pitch, yaw);

// Calculate the lateral shift
double delta_x = shift_distance * cos(yaw + M_PI_2);
double delta_y = shift_distance * sin(yaw + M_PI_2);

Check warning on line 471 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp#L470-L471

Added lines #L470 - L471 were not covered by tests

// Apply the shift
shifted_pose.point.pose.position.x += delta_x;
shifted_pose.point.pose.position.y += delta_y;

Check warning on line 475 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp#L474-L475

Added lines #L474 - L475 were not covered by tests

shifted_path.points.push_back(shifted_pose);
}

return shifted_path;

Check warning on line 480 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp#L480

Added line #L480 was not covered by tests
}

bool BehaviorPathPlannerNode::isLaneBidirectional(const lanelet::ConstLanelets & current_lanelets)
{
for (const auto & current_lanelet : current_lanelets) {
const auto left_bound_id = current_lanelet.leftBound().id();
const auto right_bound_id = current_lanelet.rightBound().id();
for (const auto & other_lanelet : current_lanelets) {
if (current_lanelet != other_lanelet) {
if (

Check warning on line 490 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp#L490

Added line #L490 was not covered by tests
left_bound_id == other_lanelet.rightBound().id() ||
right_bound_id == other_lanelet.leftBound().id()) {
return true;
}
}
}
}
return false;
}

Check warning on line 499 in planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

BehaviorPathPlannerNode::isLaneBidirectional has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.

void BehaviorPathPlannerNode::computeTurnSignal(
const std::shared_ptr<PlannerData> planner_data, const PathWithLaneId & path,
const BehaviorModuleOutput & output)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,12 @@ struct ModuleNameStamped
rclcpp::Time stamp{0, 0, RCL_ROS_TIME};
};

struct LaneletData
{
lanelet::Lanelet lanelet;
bool is_bidirectional{false};
};

struct DrivableLanes
{
lanelet::ConstLanelet right_lane;
Expand Down Expand Up @@ -240,7 +246,9 @@ struct PlannerData
node.declare_parameter<double>("ego_nearest_dist_threshold");
parameters.ego_nearest_yaw_threshold =
node.declare_parameter<double>("ego_nearest_yaw_threshold");
parameters.check_bidirectional_lane = node.declare_parameter<bool>("check_bidirectional_lane");

parameters.traffic_flow = node.declare_parameter<std::string>("traffic_flow");
drivable_area_expansion_parameters.init(node);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>

#include <string>

struct ModuleConfigParameters
{
bool enable_module{false};
Expand Down Expand Up @@ -52,6 +54,8 @@ struct BehaviorPathPlannerParameters
double turn_signal_shift_length_threshold;
double turn_signal_remaining_shift_length_threshold;
bool turn_signal_on_swerving;
bool check_bidirectional_lane;
std::string traffic_flow{"left_side"};

bool enable_akima_spline_first;
bool enable_cog_on_centerline;
Expand Down
Loading