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(lane_change): do not cancel when approaching terminal start #8381

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 @@ -92,6 +92,8 @@ class NormalLaneChange : public LaneChangeBase

bool isAbleToReturnCurrentLane() const override;

bool is_near_terminal() const final;

bool isEgoOnPreparePhase() const override;

bool isAbleToStopSafely() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,8 @@ class LaneChangeBase

virtual bool isAbleToReturnCurrentLane() const = 0;

virtual bool is_near_terminal() const = 0;

virtual LaneChangePath getLaneChangePath() const = 0;

virtual BehaviorModuleOutput getTerminalLaneChangePath() const = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
namespace autoware::behavior_path_planner::utils::lane_change::calculation
{
using behavior_path_planner::lane_change::CommonDataPtr;
using behavior_path_planner::lane_change::LCParamPtr;

/**
* @brief Calculates the distance from the ego vehicle to the terminal point.
Expand All @@ -40,6 +41,23 @@ double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr);
double calc_dist_from_pose_to_terminal_end(
const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes,
const Pose & src_pose);

/**
* @brief Calculates the minimum stopping distance to terminal start.
*
* This function computes the minimum stopping distance to terminal start based on the
* minimum lane changing velocity and the minimum longitudinal acceleration. It then
* compares this calculated distance with a pre-defined backward length buffer parameter
* and returns the larger of the two values to ensure safe lane changing.
*
* @param lc_param_ptr Shared pointer to an LCParam structure, which should include:
* - `minimum_lane_changing_velocity`: The minimum velocity required for lane changing.
* - `min_longitudinal_acc`: The minimum longitudinal acceleration used for deceleration.
* - `backward_length_buffer_for_end_of_lane`: A predefined backward buffer length parameter.
*
* @return The required backward buffer distance in meters.
*/
double calc_stopping_distance(const LCParamPtr & lc_param_ptr);
} // namespace autoware::behavior_path_planner::utils::lane_change::calculation

#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -265,6 +265,15 @@
return true;
}

if (module_type_->is_near_terminal()) {
log_debug_throttled("Unsafe, but ego is approaching terminal. Continue lane change");

Check warning on line 269 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp#L269

Added line #L269 was not covered by tests

if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) {
log_debug_throttled("Module require stopping");

Check warning on line 272 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp#L272

Added line #L272 was not covered by tests
}
maxime-clem marked this conversation as resolved.
Show resolved Hide resolved
return false;

Check warning on line 274 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp#L274

Added line #L274 was not covered by tests
}

Check warning on line 276 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

LaneChangeInterface::canTransitFailureState increases in cyclomatic complexity from 21 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.

Check warning on line 276 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

LaneChangeInterface::canTransitFailureState has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
if (module_type_->isCancelEnabled() && module_type_->isEgoOnPreparePhase()) {
if (module_type_->isStoppedAtRedTrafficLight()) {
log_debug_throttled("Stopping at traffic light while in prepare phase. Cancel lane change");
Expand Down
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_planner/autoware_behavior_path_lane_change_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 1809 to 1828, 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_planner/autoware_behavior_path_lane_change_module/src/scene.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.44 to 5.38, 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 @@ -768,6 +768,31 @@
return true;
}

bool NormalLaneChange::is_near_terminal() const

Check warning on line 771 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L771

Added line #L771 was not covered by tests
{
const auto & current_lanes = common_data_ptr_->lanes_ptr->current;

if (current_lanes.empty()) {
return true;
}

const auto & current_lanes_terminal = current_lanes.back();
const auto & lc_param_ptr = common_data_ptr_->lc_param_ptr;
const auto direction = common_data_ptr_->direction;
const auto & route_handler_ptr = common_data_ptr_->route_handler_ptr;
const auto min_lane_changing_distance = calcMinimumLaneChangeLength(

Check warning on line 783 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L780-L783

Added lines #L780 - L783 were not covered by tests
route_handler_ptr, current_lanes_terminal, *lc_param_ptr, direction);

const auto backward_buffer = calculation::calc_stopping_distance(lc_param_ptr);

Check warning on line 786 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L786

Added line #L786 was not covered by tests

const auto min_lc_dist_with_buffer =
backward_buffer + min_lane_changing_distance + lc_param_ptr->lane_change_finish_judge_buffer;

Check warning on line 789 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L789

Added line #L789 was not covered by tests
const auto dist_from_ego_to_terminal_end =
calculation::calc_ego_dist_to_terminal_end(common_data_ptr_);

Check warning on line 791 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L791

Added line #L791 was not covered by tests

return dist_from_ego_to_terminal_end < min_lc_dist_with_buffer;

Check warning on line 793 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L793

Added line #L793 was not covered by tests
}

bool NormalLaneChange::isEgoOnPreparePhase() const
{
const auto & start_position = status_.lane_change_path.info.shift_line.start.position;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@

// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
Expand Down Expand Up @@ -42,4 +43,15 @@
}
return utils::getDistanceToEndOfLane(src_pose, lanes);
}

double calc_stopping_distance(const LCParamPtr & lc_param_ptr)

Check warning on line 47 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp#L47

Added line #L47 was not covered by tests
{
// v^2 = u^2 + 2ad
const auto min_lc_vel = lc_param_ptr->minimum_lane_changing_velocity;
const auto min_lon_acc = lc_param_ptr->min_longitudinal_acc;

Check warning on line 51 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp#L50-L51

Added lines #L50 - L51 were not covered by tests
const auto min_back_dist = std::abs((min_lc_vel * min_lc_vel) / (2 * min_lon_acc));

const auto param_back_dist = lc_param_ptr->backward_length_buffer_for_end_of_lane;
return std::max(min_back_dist, param_back_dist);

Check warning on line 55 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp#L55

Added line #L55 was not covered by tests
}
} // namespace autoware::behavior_path_planner::utils::lane_change::calculation
Loading