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

feat(lane_change_module): add general method to get turn signal for LC module #6627

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 @@ -151,8 +151,6 @@ class NormalLaneChange : public LaneChangeBase
const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes) const;

TurnSignalInfo calcTurnSignalInfo() const override;

bool isValidPath(const PathWithLaneId & path) const override;

PathSafetyStatus isLaneChangePathSafe(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -218,8 +218,6 @@ class LaneChangeBase
LaneChangePaths * candidate_paths, const utils::path_safety_checker::RSSparams rss_params,
const bool is_stuck, const bool check_safety) const = 0;

virtual TurnSignalInfo calcTurnSignalInfo() const = 0;

virtual bool isValidPath(const PathWithLaneId & path) const = 0;

virtual bool isAbleToStopSafely() const = 0;
Expand Down
75 changes: 14 additions & 61 deletions planning/behavior_path_lane_change_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_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1653 to 1619, 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_lane_change_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 5.40 to 5.41, 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 @@ -480,14 +480,20 @@

TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const
{
TurnSignalInfo turn_signal_info = calcTurnSignalInfo();
const auto [turn_signal_command, distance_to_vehicle_front] = utils::getPathTurnSignal(
status_.current_lanes, status_.lane_change_path.shifted_path,
status_.lane_change_path.info.shift_line, getEgoPose(), getEgoTwist().linear.x,
planner_data_->parameters);
turn_signal_info.turn_signal.command = turn_signal_command.command;

return turn_signal_info;
const auto & pose = getEgoPose();
const auto & current_lanes = status_.current_lanes;
const auto & shift_line = status_.lane_change_path.info.shift_line;
const auto & shift_path = status_.lane_change_path.shifted_path;
const auto current_shift_length = lanelet::utils::getArcCoordinates(current_lanes, pose).distance;

Check warning on line 487 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L484-L487

Added lines #L484 - L487 were not covered by tests
constexpr bool is_driving_forward = true;
// The getBehaviorTurnSignalInfo method expects the shifted line to be generated off of the ego's
// current lane, lane change is different, so we set this flag to false.
constexpr bool egos_lane_is_shifted = false;

const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo(

Check warning on line 493 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L493

Added line #L493 was not covered by tests
shift_path, shift_line, current_lanes, current_shift_length, is_driving_forward,
egos_lane_is_shifted);
return new_signal;

Check warning on line 496 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L496

Added line #L496 was not covered by tests
}

lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const
Expand Down Expand Up @@ -1686,59 +1692,6 @@
return {};
}

TurnSignalInfo NormalLaneChange::calcTurnSignalInfo() const
{
const auto get_blinker_pose = [](const PathWithLaneId & path, const double length) {
double accumulated_length = 0.0;
for (size_t i = 0; i < path.points.size() - 1; ++i) {
accumulated_length +=
tier4_autoware_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1));
if (accumulated_length > length) {
return path.points.at(i).point.pose;
}
}

return path.points.front().point.pose;
};

const auto & path = status_.lane_change_path;
const auto & shifted_path = path.shifted_path.path;

TurnSignalInfo turn_signal_info{};

if (path.path.points.empty()) {
return turn_signal_info;
}

// desired start pose = prepare start pose
turn_signal_info.desired_start_point = std::invoke([&]() {
const auto blinker_start_duration = planner_data_->parameters.turn_signal_search_time;
const auto diff_time = path.info.duration.prepare - blinker_start_duration;
if (diff_time < 1e-5) {
return path.path.points.front().point.pose;
}

const auto current_twist = getEgoTwist();
const auto diff_length = std::abs(current_twist.linear.x) * diff_time;
return get_blinker_pose(path.path, diff_length);
});

// desired end pose
const auto length_ratio =
std::clamp(lane_change_parameters_->length_ratio_for_turn_signal_deactivation, 0.0, 1.0);
const auto desired_end_length = path.info.length.lane_changing * length_ratio;
turn_signal_info.desired_end_point = get_blinker_pose(shifted_path, desired_end_length);

// required start pose = lane changing start pose
turn_signal_info.required_start_point = path.info.shift_line.start;

// required end pose = in the middle of the lane change
const auto mid_lane_change_length = path.info.length.lane_changing / 2;
turn_signal_info.required_end_point = get_blinker_pose(shifted_path, mid_lane_change_length);

return turn_signal_info;
}

bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const
{
const auto & route_handler = planner_data_->route_handler;
Expand Down
Loading