Skip to content

Commit

Permalink
fix(bpp): overwrite turn signal by latter module
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed May 17, 2024
1 parent 3d849e9 commit 5bb25a0
Show file tree
Hide file tree
Showing 5 changed files with 73 additions and 14 deletions.
2 changes: 1 addition & 1 deletion planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -928,7 +928,7 @@ BehaviorModuleOutput AvoidanceModule::plan()
helper_->getEgoShift(), is_driving_forward, egos_lane_is_shifted);

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(
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1092,7 +1092,7 @@ void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output)
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
const auto new_signal = calcTurnSignalInfo();
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
output.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
Expand Down
8 changes: 4 additions & 4 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ TurnSignalInfo NormalLaneChange::get_current_turn_signal_info()
}

// check the priority of turn signals
return getTurnSignalDecider().use_prior_turn_signal(
return getTurnSignalDecider().overwrite_turn_signal(
path, current_pose, current_nearest_seg_idx, original_turn_signal_info,
current_turn_signal_info, nearest_dist_threshold, nearest_yaw_threshold);
}
Expand All @@ -226,7 +226,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
output.path = abort_path_->path;
extendOutputDrivableArea(output);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
Expand All @@ -252,7 +252,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
extendOutputDrivableArea(output);

const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
Expand Down Expand Up @@ -297,7 +297,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()
extendOutputDrivableArea(output);

const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,17 @@ struct TurnSignalInfo
hazard_signal.command = HazardLightsCommand::NO_COMMAND;
}

TurnSignalInfo(const Pose & start, const Pose & end)
{
turn_signal.command = TurnIndicatorsCommand::NO_COMMAND;
hazard_signal.command = HazardLightsCommand::NO_COMMAND;

desired_start_point = start;
desired_end_point = end;
required_start_point = start;
required_end_point = end;
}

// desired turn signal
TurnIndicatorsCommand turn_signal;
HazardLightsCommand hazard_signal;
Expand Down Expand Up @@ -93,6 +104,11 @@ class TurnSignalDecider
const TurnSignalInfo & intersection_signal_info, const TurnSignalInfo & behavior_signal_info,
const double nearest_dist_threshold, const double nearest_yaw_threshold);

TurnSignalInfo overwrite_turn_signal(
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
const double nearest_dist_threshold, const double nearest_yaw_threshold);

TurnSignalInfo use_prior_turn_signal(
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
Expand Down
59 changes: 51 additions & 8 deletions planning/behavior_path_planner_common/src/turn_signal_decider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -392,6 +392,39 @@ TurnIndicatorsCommand TurnSignalDecider::resolve_turn_signal(
return intersection_signal_info.turn_signal;
}

TurnSignalInfo TurnSignalDecider::overwrite_turn_signal(
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
const double nearest_dist_threshold, const double nearest_yaw_threshold)
{
if (original_signal.turn_signal.command == TurnIndicatorsCommand::NO_COMMAND) {
return new_signal;
}

if (original_signal.turn_signal.command == TurnIndicatorsCommand::DISABLE) {
return new_signal;
}

const auto get_distance = [&](const Pose & input_point) {
const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold);
return motion_utils::calcSignedArcLength(
path.points, current_pose.position, current_seg_idx, input_point.position, nearest_seg_idx);
};

const auto & original_desired_end_point = original_signal.desired_end_point;
const auto & new_desired_start_point = new_signal.desired_start_point;

const double dist_to_original_desired_end =
get_distance(original_desired_end_point) - base_link2front_;
const double dist_to_new_desired_start = get_distance(new_desired_start_point) - base_link2front_;
if (dist_to_new_desired_start > dist_to_original_desired_end) {
return original_signal;
}

return new_signal;
}

TurnSignalInfo TurnSignalDecider::use_prior_turn_signal(
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
Expand Down Expand Up @@ -615,6 +648,8 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted,
const bool override_ego_stopped_check, const bool is_pull_out) const
{
using tier4_autoware_utils::getPose;

constexpr double THRESHOLD = 0.1;
const auto & p = parameters;
const auto & rh = route_handler;
Expand Down Expand Up @@ -670,12 +705,14 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(

// 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 std::make_pair(TurnSignalInfo{}, true);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), true);
}

// If the vehicle does not shift anymore, we turn off the blinker
if (std::fabs(end_shift_length - current_shift_length) < THRESHOLD) {
return std::make_pair(TurnSignalInfo{}, true);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), true);
}

const auto get_command = [](const auto & shift_length) {
Expand All @@ -690,7 +727,8 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
p.vehicle_info.max_longitudinal_offset_m;

if (signal_prepare_distance < ego_front_to_shift_start) {
return std::make_pair(TurnSignalInfo{}, false);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), false);
}

const auto blinker_start_pose = path.path.points.at(shift_line.start_idx).point.pose;
Expand All @@ -707,13 +745,15 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
turn_signal_info.turn_signal.command = get_command(relative_shift_length);

if (!p.turn_signal_on_swerving) {
return std::make_pair(turn_signal_info, false);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), false);
}

lanelet::ConstLanelet lanelet;
const auto query_pose = (egos_lane_is_shifted) ? shift_line.end : shift_line.start;
if (!rh->getClosestLaneletWithinRoute(query_pose, &lanelet)) {
return std::make_pair(TurnSignalInfo{}, true);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), true);
}

const auto left_same_direction_lane = rh->getLeftLanelet(lanelet, true, true);
Expand All @@ -728,13 +768,15 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
!is_pull_out && !existShiftSideLane(
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
p.turn_signal_shift_length_threshold)) {
return std::make_pair(TurnSignalInfo{}, true);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), true);
}

// Check if the ego will cross lane bounds.
// Note that pull out requires blinkers, even if the ego does not cross lane bounds
if (!is_pull_out && !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) {
return std::make_pair(TurnSignalInfo{}, true);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), true);
}

// If the ego has stopped and its close to completing its shift, turn off the blinkers
Expand All @@ -743,7 +785,8 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
if (isNearEndOfShift(
start_shift_length, end_shift_length, ego_pose.position, current_lanelets,
p.turn_signal_shift_length_threshold)) {
return std::make_pair(TurnSignalInfo{}, true);
return std::make_pair(
TurnSignalInfo(getPose(path.path.points.front()), getPose(path.path.points.back())), true);
}
}

Expand Down

0 comments on commit 5bb25a0

Please sign in to comment.