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(goal_planner): add general turnsignalinfo method for goal planner #6629

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 @@ -37,6 +37,8 @@
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>

#include <lanelet2_core/Forward.h>

#include <atomic>
#include <deque>
#include <limits>
Expand Down Expand Up @@ -525,14 +527,15 @@ class GoalPlannerModule : public SceneModuleInterface
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;

// output setter
void setOutput(BehaviorModuleOutput & output) const;
void setOutput(BehaviorModuleOutput & output);
void updatePreviousData();

void setModifiedGoal(BehaviorModuleOutput & output) const;
void setTurnSignalInfo(BehaviorModuleOutput & output) const;
void setTurnSignalInfo(BehaviorModuleOutput & output);

// new turn signal
TurnSignalInfo calcTurnSignalInfo() const;
TurnSignalInfo calcTurnSignalInfo();
std::optional<lanelet::Id> ignore_signal_{std::nullopt};

std::optional<BehaviorModuleOutput> last_previous_module_output_{};
bool hasPreviousModulePathShapeChanged() const;
Expand Down
111 changes: 83 additions & 28 deletions planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_goal_planner_module/src/goal_planner_module.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 1717 to 1738, 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_goal_planner_module/src/goal_planner_module.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.06 to 5.09, 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 @@ -893,7 +893,7 @@
return utils::generateDrivableLanesWithShoulderLanes(current_lanes, pull_over_lanes);
}

void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const
void GoalPlannerModule::setOutput(BehaviorModuleOutput & output)

Check warning on line 896 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L896

Added line #L896 was not covered by tests
{
output.reference_path = getPreviousModuleOutput().reference_path;

Expand Down Expand Up @@ -966,7 +966,7 @@
}
}

void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output) const
void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output)

Check warning on line 969 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L969

Added line #L969 was not covered by tests
{
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
const auto new_signal = calcTurnSignalInfo();
Expand Down Expand Up @@ -1573,43 +1573,98 @@
parameters_->th_arrived_distance;
}

TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const
TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo()

Check warning on line 1576 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1576

Added line #L1576 was not covered by tests
{
TurnSignalInfo turn_signal{}; // output
const auto path = thread_safe_data_.get_pull_over_path()->getFullPath();
if (path.points.empty()) return getPreviousModuleOutput().turn_signal_info;

Check warning on line 1579 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1578-L1579

Added lines #L1578 - L1579 were not covered by tests

const auto & current_pose = planner_data_->self_odometry->pose.pose;
const auto & start_pose = thread_safe_data_.get_pull_over_path()->start_pose;
const auto & end_pose = thread_safe_data_.get_pull_over_path()->end_pose;
const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath();

// calc TurnIndicatorsCommand
{
const double distance_to_end =
calcSignedArcLength(full_path.points, current_pose.position, end_pose.position);
const bool is_before_end_pose = distance_to_end >= 0.0;
if (is_before_end_pose) {
if (left_side_parking_) {
turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT;
} else {
turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
}
} else {
turn_signal.turn_signal.command = TurnIndicatorsCommand::NO_COMMAND;
const auto shift_start_idx = motion_utils::findNearestIndex(path.points, start_pose.position);
const auto shift_end_idx = motion_utils::findNearestIndex(path.points, end_pose.position);

Check warning on line 1586 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1585-L1586

Added lines #L1585 - L1586 were not covered by tests

const auto is_ignore_signal = [this](const lanelet::Id & id) {
if (!ignore_signal_.has_value()) {

Check warning on line 1589 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1589

Added line #L1589 was not covered by tests
return false;
}
return ignore_signal_.value() == id;

Check warning on line 1592 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1592

Added line #L1592 was not covered by tests
};

const auto update_ignore_signal = [this](const lanelet::Id & id, const bool is_ignore) {
return is_ignore ? std::make_optional(id) : std::nullopt;

Check warning on line 1596 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1596

Added line #L1596 was not covered by tests
};

const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes(
planner_data_, parameters_->backward_goal_search_length,

Check warning on line 1600 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1600

Added line #L1600 was not covered by tests
parameters_->forward_goal_search_length,
/*forward_only_in_route*/ false);

Check warning on line 1602 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1602

Added line #L1602 was not covered by tests

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

Check warning on line 1605 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1604-L1605

Added lines #L1604 - L1605 were not covered by tests
}

// calc desired/required start/end point
{
// ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds
// before starting pull_over
turn_signal.desired_start_point =
last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose;
turn_signal.desired_end_point = end_pose;
turn_signal.required_start_point = start_pose;
turn_signal.required_end_point = end_pose;
lanelet::Lanelet closest_lanelet;
lanelet::utils::query::getClosestLanelet(current_lanes, current_pose, &closest_lanelet);

Check warning on line 1609 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1609

Added line #L1609 was not covered by tests

if (is_ignore_signal(closest_lanelet.id())) {
return getPreviousModuleOutput().turn_signal_info;

Check warning on line 1612 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1611-L1612

Added lines #L1611 - L1612 were not covered by tests
}

return turn_signal;
const double current_shift_length =
lanelet::utils::getArcCoordinates(current_lanes, current_pose).distance;

Check warning on line 1616 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1616

Added line #L1616 was not covered by tests

constexpr bool egos_lane_is_shifted = true;
constexpr bool is_driving_forward = true;

constexpr bool is_pull_out = false;
const bool override_ego_stopped_check = std::invoke([&]() {
if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::SHIFT) {

Check warning on line 1623 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1622-L1623

Added lines #L1622 - L1623 were not covered by tests
return false;
}
constexpr double distance_threshold = 1.0;
const auto stop_point =
thread_safe_data_.get_pull_over_path()->partial_paths.front().points.back();
const double distance_from_ego_to_stop_point = std::abs(motion_utils::calcSignedArcLength(
path.points, stop_point.point.pose.position, current_pose.position));
return distance_from_ego_to_stop_point < distance_threshold;

Check warning on line 1631 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1628-L1631

Added lines #L1628 - L1631 were not covered by tests
});

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

Check warning on line 1634 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1634

Added line #L1634 was not covered by tests
path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length, is_driving_forward,
egos_lane_is_shifted, override_ego_stopped_check, is_pull_out);
ignore_signal_ = update_ignore_signal(closest_lanelet.id(), is_ignore);

Check warning on line 1637 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1637

Added line #L1637 was not covered by tests

return new_signal;

Check warning on line 1639 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1639

Added line #L1639 was not covered by tests
// // calc TurnIndicatorsCommand
// {
// const double distance_to_end =
// calcSignedArcLength(full_path.points, current_pose.position, end_pose.position);
// const bool is_before_end_pose = distance_to_end >= 0.0;
// if (is_before_end_pose) {
// if (left_side_parking_) {
// turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT;
// } else {
// turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
// }
// } else {
// turn_signal.turn_signal.command = TurnIndicatorsCommand::NO_COMMAND;
// }
// }

// // calc desired/required start/end point
// {
// // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds
// // before starting pull_over
// turn_signal.desired_start_point =
// last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose;
// turn_signal.desired_end_point = end_pose;
// turn_signal.required_start_point = start_pose;
// turn_signal.required_end_point = end_pose;
// }

// return turn_signal;
}

bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const
Expand Down
Loading