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(avoidance): turn off blinker when the ego return original lane #6300

Merged
merged 4 commits into from
Feb 27, 2024
Merged
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 @@ -443,9 +443,6 @@ struct AvoidLine : public ShiftLine
// Distance from ego to end point in Frenet
double end_longitudinal = 0.0;

// for unique_id
UUID id{};

// for the case the point is created by merge other points
std::vector<UUID> parent_ids{};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,8 @@ class AvoidanceModule : public SceneModuleInterface

bool safe_{true};

std::optional<UUID> ignore_signal_{std::nullopt};

std::shared_ptr<AvoidanceHelper> helper_;

std::shared_ptr<AvoidanceParameters> parameters_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ double calcDistanceToAvoidStartLine(
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters);

TurnSignalInfo calcTurnSignalInfo(
std::pair<TurnSignalInfo, bool> calcTurnSignalInfo(
const ShiftedPath & path, const ShiftLine & shift_line, const double current_shift_length,
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data);
} // namespace behavior_path_planner::utils::avoidance
Expand Down
17 changes: 16 additions & 1 deletion planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1171 to 1183, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/scene.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 4.86 to 4.93, 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 @@ -918,19 +918,34 @@

BehaviorModuleOutput output;

const auto is_ignore_signal = [this](const UUID & uuid) {

Check warning on line 921 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L921

Added line #L921 was not covered by tests
if (!ignore_signal_.has_value()) {
return false;
}

return ignore_signal_.value() == uuid;
};

const auto update_ignore_signal = [this](const UUID & uuid, const bool is_ignore) {
ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt;
};

// turn signal info
if (path_shifter_.getShiftLines().empty()) {
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
} else if (is_ignore_signal(path_shifter_.getShiftLines().front().id)) {
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;

Check warning on line 937 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L937

Added line #L937 was not covered by tests
} else {
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
const auto new_signal = utils::avoidance::calcTurnSignalInfo(
const auto [new_signal, is_ignore] = utils::avoidance::calcTurnSignalInfo(
linear_shift_path, path_shifter_.getShiftLines().front(), helper_->getEgoShift(), avoid_data_,
planner_data_);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
update_ignore_signal(path_shifter_.getShiftLines().front().id, is_ignore);

Check warning on line 948 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

AvoidanceModule::plan increases in cyclomatic complexity from 9 to 12, 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.
}

// sparse resampling for computational cost
Expand Down
97 changes: 71 additions & 26 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1845 to 1882, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check warning on line 1 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Number of Functions in a Single Module

This module has 79 functions, threshold = 75. This file contains too many functions. Beyond a certain threshold, more functions lower the code health.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 5.16 to 4.94, 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 @@ -250,56 +250,73 @@
base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end());
}

bool isAvoidShift(
const double start_shift_length, const double end_shift_length, const double threshold)
{
return std::abs(start_shift_length) < threshold && std::abs(end_shift_length) > threshold;
}

bool isReturnShift(
const double start_shift_length, const double end_shift_length, const double threshold)
{
return std::abs(start_shift_length) > threshold && std::abs(end_shift_length) < threshold;
}

bool isLeftMiddleShift(
const double start_shift_length, const double end_shift_length, const double threshold)
{
return start_shift_length > threshold && end_shift_length > threshold;
}

bool isRightMiddleShift(
const double start_shift_length, const double end_shift_length, const double threshold)
{
return start_shift_length < threshold && end_shift_length < threshold;
}

bool existShiftSideLane(
const double start_shift_length, const double end_shift_length, const bool no_left_lanes,
const bool no_right_lanes)
const bool no_right_lanes, const double threshold)
{
constexpr double THRESHOLD = 0.1;
const auto relative_shift_length = end_shift_length - start_shift_length;

const auto avoid_shift =
std::abs(start_shift_length) < THRESHOLD && std::abs(end_shift_length) > THRESHOLD;
if (avoid_shift) {
if (isAvoidShift(start_shift_length, end_shift_length, threshold)) {
// Left avoid. But there is no adjacent lane. No need blinker.
if (relative_shift_length > 0.0 && no_left_lanes) {
return false;
}

// Right avoid. But there is no adjacent lane. No need blinker.
if (relative_shift_length < 0.0 && no_right_lanes) {
return false;
}
}

const auto return_shift =
std::abs(start_shift_length) > THRESHOLD && std::abs(end_shift_length) < THRESHOLD;
if (return_shift) {
if (isReturnShift(start_shift_length, end_shift_length, threshold)) {
// Right return. But there is no adjacent lane. No need blinker.
if (relative_shift_length > 0.0 && no_right_lanes) {
return false;
}

// Left return. But there is no adjacent lane. No need blinker.
if (relative_shift_length < 0.0 && no_left_lanes) {
return false;
}
}

const auto left_middle_shift = start_shift_length > THRESHOLD && end_shift_length > THRESHOLD;
if (left_middle_shift) {
if (isLeftMiddleShift(start_shift_length, end_shift_length, threshold)) {
// Left avoid. But there is no adjacent lane. No need blinker.
if (relative_shift_length > 0.0 && no_left_lanes) {
return false;
}

// Left return. But there is no adjacent lane. No need blinker.
if (relative_shift_length < 0.0 && no_left_lanes) {
return false;
}
}

const auto right_middle_shift = start_shift_length < THRESHOLD && end_shift_length < THRESHOLD;
if (right_middle_shift) {
if (isRightMiddleShift(start_shift_length, end_shift_length, threshold)) {

Check notice on line 319 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

existShiftSideLane decreases in cyclomatic complexity from 25 to 21, 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.

Check notice on line 319 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Excess Number of Function Arguments

existShiftSideLane has 5 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
// Right avoid. But there is no adjacent lane. No need blinker.
if (relative_shift_length < 0.0 && no_right_lanes) {
return false;
Expand All @@ -314,6 +331,23 @@
return true;
}

bool isNearEndOfShift(

Check warning on line 334 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L334

Added line #L334 was not covered by tests
const double start_shift_length, const double end_shift_length, const Point & ego_pos,
const lanelet::ConstLanelets & original_lanes, const double threshold)
{
using boost::geometry::within;
using lanelet::utils::to2D;
using lanelet::utils::conversion::toLaneletPoint;

if (!isReturnShift(start_shift_length, end_shift_length, threshold)) {
return false;
}

return std::any_of(original_lanes.begin(), original_lanes.end(), [&ego_pos](const auto & lane) {

Check warning on line 346 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L346

Added line #L346 was not covered by tests
return within(to2D(toLaneletPoint(ego_pos)), lane.polygon2d().basicPolygon());
});

Check warning on line 348 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L348

Added line #L348 was not covered by tests
}

Check notice on line 349 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Excess Number of Function Arguments

isNearEndOfShift has 5 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.

bool straddleRoadBound(
const ShiftedPath & path, const ShiftLine & shift_line, const lanelet::ConstLanelets & lanes,
const vehicle_info_util::VehicleInfo & vehicle_info)
Expand Down Expand Up @@ -2323,7 +2357,7 @@
return distance_to_return_dead_line;
}

TurnSignalInfo calcTurnSignalInfo(
std::pair<TurnSignalInfo, bool> calcTurnSignalInfo(

Check warning on line 2360 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2360

Added line #L2360 was not covered by tests
Copy link
Contributor

@Owen-Liuyuxuan Owen-Liuyuxuan Feb 20, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the refactoring.
Personally, with the current change, I would suggest renaming this THRESHOLD into something like current_shift_threshold because it is no longer a "general" threshold in this calcTurnSignalInfo function.
(I am not familiar with the extra influences of renaming this parameter, so it is just a small idea on readability)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed in e677db4.

const ShiftedPath & path, const ShiftLine & shift_line, const double current_shift_length,
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data)
{
Expand All @@ -2335,22 +2369,22 @@

if (shift_line.start_idx + 1 > path.shift_length.size()) {
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2372 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2372

Added line #L2372 was not covered by tests
}

if (shift_line.start_idx + 1 > path.path.points.size()) {
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2377 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2377

Added line #L2377 was not covered by tests
}

if (shift_line.end_idx + 1 > path.shift_length.size()) {
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2382 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2382

Added line #L2382 was not covered by tests
}

if (shift_line.end_idx + 1 > path.path.points.size()) {
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2387 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2387

Added line #L2387 was not covered by tests
}

const auto start_shift_length = path.shift_length.at(shift_line.start_idx);
Expand All @@ -2359,12 +2393,12 @@

// If shift length is shorter than the threshold, it does not need to turn on blinkers
if (std::fabs(relative_shift_length) < p.turn_signal_shift_length_threshold) {
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2396 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2396

Added line #L2396 was not covered by tests
}

// If the vehicle does not shift anymore, we turn off the blinker
if (std::fabs(path.shift_length.at(shift_line.end_idx) - current_shift_length) < THRESHOLD) {
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2401 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2401

Added line #L2401 was not covered by tests
}

const auto get_command = [](const auto & shift_length) {
Expand All @@ -2379,7 +2413,7 @@
p.vehicle_info.max_longitudinal_offset_m;

if (signal_prepare_distance < ego_front_to_shift_start) {
return {};
return std::make_pair(TurnSignalInfo{}, false);

Check warning on line 2416 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2416

Added line #L2416 was not covered by tests
}

const auto blinker_start_pose = path.path.points.at(shift_line.start_idx).point.pose;
Expand All @@ -2396,12 +2430,12 @@
turn_signal_info.turn_signal.command = get_command(relative_shift_length);

if (!p.turn_signal_on_swerving) {
return turn_signal_info;
return std::make_pair(turn_signal_info, false);
}

lanelet::ConstLanelet lanelet;
if (!rh->getClosestLaneletWithinRoute(shift_line.end, &lanelet)) {
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2438 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2438

Added line #L2438 was not covered by tests
}

const auto left_same_direction_lane = rh->getLeftLanelet(lanelet, true, true);
Expand All @@ -2412,14 +2446,25 @@
const auto has_right_lane =
right_same_direction_lane.has_value() || !right_opposite_lanes.empty();

if (!existShiftSideLane(start_shift_length, end_shift_length, !has_left_lane, !has_right_lane)) {
return {};
if (!existShiftSideLane(
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,

Check warning on line 2450 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2449-L2450

Added lines #L2449 - L2450 were not covered by tests
p.turn_signal_shift_length_threshold)) {
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2452 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2452

Added line #L2452 was not covered by tests
}

if (!straddleRoadBound(path, shift_line, data.current_lanelets, p.vehicle_info)) {
return {};
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2456 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2456

Added line #L2456 was not covered by tests
}

constexpr double STOPPED_THRESHOLD = 0.1; // [m/s]
if (ego_speed < STOPPED_THRESHOLD) {
if (isNearEndOfShift(
start_shift_length, end_shift_length, ego_pose.position, data.current_lanelets,
p.turn_signal_shift_length_threshold)) {
return std::make_pair(TurnSignalInfo{}, true);

Check warning on line 2464 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L2464

Added line #L2464 was not covered by tests
}
}

return turn_signal_info;
return std::make_pair(turn_signal_info, false);

Check notice on line 2468 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

calcTurnSignalInfo increases in cyclomatic complexity from 16 to 18, 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.
}
} // namespace behavior_path_planner::utils::avoidance
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,11 @@

#include <rclcpp/clock.hpp>
#include <rclcpp/logging.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>

#include <optional>
#include <string>
Expand All @@ -31,9 +33,13 @@
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using tier4_autoware_utils::generateUUID;
using unique_identifier_msgs::msg::UUID;

struct ShiftLine
{
ShiftLine() : id(generateUUID()) {}

Check warning on line 41 in planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp#L41

Added line #L41 was not covered by tests

Pose start{}; // shift start point in absolute coordinate
Pose end{}; // shift start point in absolute coordinate

Expand All @@ -45,6 +51,9 @@

size_t start_idx{}; // associated start-point index for the reference path
size_t end_idx{}; // associated end-point index for the reference path

// for unique_id
UUID id{};
};
using ShiftLineArray = std::vector<ShiftLine>;

Expand Down
Loading