Skip to content

Commit 4daa6a9

Browse files
authored
fix(bpp): overwrite turn signal by latter module (#7045)
* fix(bpp): overwrite turn signal by latter module Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): return previous module turn signal if it's in success state Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): don't output turn signal if there is huge lateral deveation Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor: small update Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore: use lower case Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor: remove redundant function call Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent f061073 commit 4daa6a9

File tree

5 files changed

+81
-14
lines changed

5 files changed

+81
-14
lines changed

planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp

+13-1
Original file line numberDiff line numberDiff line change
@@ -867,10 +867,12 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan()
867867

868868
if (data.state == AvoidanceState::SUCCEEDED) {
869869
removeRegisteredShiftLines(State::SUCCEEDED);
870+
return getPreviousModuleOutput();
870871
}
871872

872873
if (data.state == AvoidanceState::CANCEL) {
873874
removeRegisteredShiftLines(State::FAILED);
875+
return getPreviousModuleOutput();
874876
}
875877

876878
if (data.yield_required) {
@@ -915,11 +917,21 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan()
915917
ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt;
916918
};
917919

920+
const auto is_large_deviation = [this](const auto & path) {
921+
constexpr double threshold = 1.0;
922+
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(path.points);
923+
const auto lateral_deviation =
924+
motion_utils::calcLateralOffset(path.points, getEgoPosition(), current_seg_idx);
925+
return std::abs(lateral_deviation) > threshold;
926+
};
927+
918928
// turn signal info
919929
if (path_shifter_.getShiftLines().empty()) {
920930
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
921931
} else if (is_ignore_signal(path_shifter_.getShiftLines().front().id)) {
922932
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
933+
} else if (is_large_deviation(spline_shift_path.path)) {
934+
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
923935
} else {
924936
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
925937

@@ -930,7 +942,7 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan()
930942
helper_->getEgoShift(), is_driving_forward, egos_lane_is_shifted);
931943

932944
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points);
933-
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
945+
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
934946
spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
935947
planner_data_->parameters.ego_nearest_dist_threshold,
936948
planner_data_->parameters.ego_nearest_yaw_threshold);

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1092,7 +1092,7 @@ void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output)
10921092
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
10931093
const auto new_signal = calcTurnSignalInfo();
10941094
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
1095-
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
1095+
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
10961096
output.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
10971097
planner_data_->parameters.ego_nearest_dist_threshold,
10981098
planner_data_->parameters.ego_nearest_yaw_threshold);

planning/behavior_path_lane_change_module/src/scene.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -204,7 +204,7 @@ TurnSignalInfo NormalLaneChange::get_current_turn_signal_info()
204204
}
205205

206206
// check the priority of turn signals
207-
return getTurnSignalDecider().use_prior_turn_signal(
207+
return getTurnSignalDecider().overwrite_turn_signal(
208208
path, current_pose, current_nearest_seg_idx, original_turn_signal_info,
209209
current_turn_signal_info, nearest_dist_threshold, nearest_yaw_threshold);
210210
}
@@ -226,7 +226,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
226226
output.path = abort_path_->path;
227227
extendOutputDrivableArea(output);
228228
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
229-
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
229+
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
230230
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
231231
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
232232
planner_data_->parameters.ego_nearest_yaw_threshold);
@@ -252,7 +252,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
252252
extendOutputDrivableArea(output);
253253

254254
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
255-
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
255+
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
256256
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
257257
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
258258
planner_data_->parameters.ego_nearest_yaw_threshold);
@@ -297,7 +297,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()
297297
extendOutputDrivableArea(output);
298298

299299
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
300-
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
300+
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
301301
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
302302
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
303303
planner_data_->parameters.ego_nearest_yaw_threshold);

planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp

+16
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,17 @@ struct TurnSignalInfo
6464
hazard_signal.command = HazardLightsCommand::NO_COMMAND;
6565
}
6666

67+
TurnSignalInfo(const Pose & start, const Pose & end)
68+
{
69+
turn_signal.command = TurnIndicatorsCommand::NO_COMMAND;
70+
hazard_signal.command = HazardLightsCommand::NO_COMMAND;
71+
72+
desired_start_point = start;
73+
desired_end_point = end;
74+
required_start_point = start;
75+
required_end_point = end;
76+
}
77+
6778
// desired turn signal
6879
TurnIndicatorsCommand turn_signal;
6980
HazardLightsCommand hazard_signal;
@@ -93,6 +104,11 @@ class TurnSignalDecider
93104
const TurnSignalInfo & intersection_signal_info, const TurnSignalInfo & behavior_signal_info,
94105
const double nearest_dist_threshold, const double nearest_yaw_threshold);
95106

107+
TurnSignalInfo overwrite_turn_signal(
108+
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
109+
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
110+
const double nearest_dist_threshold, const double nearest_yaw_threshold) const;
111+
96112
TurnSignalInfo use_prior_turn_signal(
97113
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
98114
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,

planning/behavior_path_planner_common/src/turn_signal_decider.cpp

+47-8
Original file line numberDiff line numberDiff line change
@@ -392,6 +392,40 @@ TurnIndicatorsCommand TurnSignalDecider::resolve_turn_signal(
392392
return intersection_signal_info.turn_signal;
393393
}
394394

395+
TurnSignalInfo TurnSignalDecider::overwrite_turn_signal(
396+
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
397+
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
398+
const double nearest_dist_threshold, const double nearest_yaw_threshold) const
399+
{
400+
if (original_signal.turn_signal.command == TurnIndicatorsCommand::NO_COMMAND) {
401+
return new_signal;
402+
}
403+
404+
if (original_signal.turn_signal.command == TurnIndicatorsCommand::DISABLE) {
405+
return new_signal;
406+
}
407+
408+
const auto get_distance = [&](const Pose & input_point) {
409+
const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
410+
path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold);
411+
return motion_utils::calcSignedArcLength(
412+
path.points, current_pose.position, current_seg_idx, input_point.position,
413+
nearest_seg_idx) -
414+
base_link2front_;
415+
};
416+
417+
const auto & original_desired_end_point = original_signal.desired_end_point;
418+
const auto & new_desired_start_point = new_signal.desired_start_point;
419+
420+
const double dist_to_original_desired_end = get_distance(original_desired_end_point);
421+
const double dist_to_new_desired_start = get_distance(new_desired_start_point);
422+
if (dist_to_new_desired_start > dist_to_original_desired_end) {
423+
return original_signal;
424+
}
425+
426+
return new_signal;
427+
}
428+
395429
TurnSignalInfo TurnSignalDecider::use_prior_turn_signal(
396430
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
397431
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
@@ -615,6 +649,8 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
615649
const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted,
616650
const bool override_ego_stopped_check, const bool is_pull_out) const
617651
{
652+
using tier4_autoware_utils::getPose;
653+
618654
const auto & p = parameters;
619655
const auto & rh = route_handler;
620656
const auto & ego_pose = self_odometry->pose.pose;
@@ -667,16 +703,19 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
667703

668704
const auto relative_shift_length = end_shift_length - start_shift_length;
669705

706+
const auto p_path_start = getPose(path.path.points.front());
707+
const auto p_path_end = getPose(path.path.points.back());
708+
670709
// If shift length is shorter than the threshold, it does not need to turn on blinkers
671710
if (std::fabs(relative_shift_length) < p.turn_signal_shift_length_threshold) {
672-
return std::make_pair(TurnSignalInfo{}, true);
711+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
673712
}
674713

675714
// If the vehicle does not shift anymore, we turn off the blinker
676715
if (
677716
std::fabs(end_shift_length - current_shift_length) <
678717
p.turn_signal_remaining_shift_length_threshold) {
679-
return std::make_pair(TurnSignalInfo{}, true);
718+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
680719
}
681720

682721
const auto get_command = [](const auto & shift_length) {
@@ -691,7 +730,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
691730
p.vehicle_info.max_longitudinal_offset_m;
692731

693732
if (signal_prepare_distance < ego_front_to_shift_start) {
694-
return std::make_pair(TurnSignalInfo{}, false);
733+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), false);
695734
}
696735

697736
const auto blinker_start_pose = path.path.points.at(shift_line.start_idx).point.pose;
@@ -708,13 +747,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
708747
turn_signal_info.turn_signal.command = get_command(relative_shift_length);
709748

710749
if (!p.turn_signal_on_swerving) {
711-
return std::make_pair(turn_signal_info, false);
750+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), false);
712751
}
713752

714753
lanelet::ConstLanelet lanelet;
715754
const auto query_pose = (egos_lane_is_shifted) ? shift_line.end : shift_line.start;
716755
if (!rh->getClosestLaneletWithinRoute(query_pose, &lanelet)) {
717-
return std::make_pair(TurnSignalInfo{}, true);
756+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
718757
}
719758

720759
const auto left_same_direction_lane = rh->getLeftLanelet(lanelet, true, true);
@@ -729,13 +768,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
729768
!is_pull_out && !existShiftSideLane(
730769
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
731770
p.turn_signal_shift_length_threshold)) {
732-
return std::make_pair(TurnSignalInfo{}, true);
771+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
733772
}
734773

735774
// Check if the ego will cross lane bounds.
736775
// Note that pull out requires blinkers, even if the ego does not cross lane bounds
737776
if (!is_pull_out && !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) {
738-
return std::make_pair(TurnSignalInfo{}, true);
777+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
739778
}
740779

741780
// If the ego has stopped and its close to completing its shift, turn off the blinkers
@@ -744,7 +783,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
744783
if (isNearEndOfShift(
745784
start_shift_length, end_shift_length, ego_pose.position, current_lanelets,
746785
p.turn_signal_shift_length_threshold)) {
747-
return std::make_pair(TurnSignalInfo{}, true);
786+
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
748787
}
749788
}
750789

0 commit comments

Comments
 (0)