Skip to content

Commit 3f1ae9a

Browse files
committed
Revert "fix(bpp): overwrite turn signal by latter module (autowarefoundation#7045)"
This reverts commit bf0e56f.
1 parent 8e8b0e8 commit 3f1ae9a

File tree

5 files changed

+14
-81
lines changed

5 files changed

+14
-81
lines changed

planning/behavior_path_avoidance_module/src/scene.cpp

+1-13
Original file line numberDiff line numberDiff line change
@@ -855,12 +855,10 @@ BehaviorModuleOutput AvoidanceModule::plan()
855855

856856
if (data.state == AvoidanceState::SUCCEEDED) {
857857
removeRegisteredShiftLines(State::SUCCEEDED);
858-
return getPreviousModuleOutput();
859858
}
860859

861860
if (data.state == AvoidanceState::CANCEL) {
862861
removeRegisteredShiftLines(State::FAILED);
863-
return getPreviousModuleOutput();
864862
}
865863

866864
if (data.yield_required) {
@@ -903,21 +901,11 @@ BehaviorModuleOutput AvoidanceModule::plan()
903901
ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt;
904902
};
905903

906-
const auto is_large_deviation = [this](const auto & path) {
907-
constexpr double threshold = 1.0;
908-
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(path.points);
909-
const auto lateral_deviation =
910-
motion_utils::calcLateralOffset(path.points, getEgoPosition(), current_seg_idx);
911-
return std::abs(lateral_deviation) > threshold;
912-
};
913-
914904
// turn signal info
915905
if (path_shifter_.getShiftLines().empty()) {
916906
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
917907
} else if (is_ignore_signal(path_shifter_.getShiftLines().front().id)) {
918908
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
919-
} else if (is_large_deviation(spline_shift_path.path)) {
920-
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
921909
} else {
922910
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
923911

@@ -928,7 +916,7 @@ BehaviorModuleOutput AvoidanceModule::plan()
928916
helper_->getEgoShift(), is_driving_forward, egos_lane_is_shifted);
929917

930918
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points);
931-
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
919+
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
932920
spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
933921
planner_data_->parameters.ego_nearest_dist_threshold,
934922
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
@@ -1094,7 +1094,7 @@ void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output)
10941094
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
10951095
const auto new_signal = calcTurnSignalInfo();
10961096
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
1097-
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
1097+
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
10981098
output.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
10991099
planner_data_->parameters.ego_nearest_dist_threshold,
11001100
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().overwrite_turn_signal(
207+
return getTurnSignalDecider().use_prior_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.overwrite_turn_signal(
229+
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_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.overwrite_turn_signal(
255+
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_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.overwrite_turn_signal(
300+
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_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,17 +64,6 @@ 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-
7867
// desired turn signal
7968
TurnIndicatorsCommand turn_signal;
8069
HazardLightsCommand hazard_signal;
@@ -104,11 +93,6 @@ class TurnSignalDecider
10493
const TurnSignalInfo & intersection_signal_info, const TurnSignalInfo & behavior_signal_info,
10594
const double nearest_dist_threshold, const double nearest_yaw_threshold);
10695

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-
11296
TurnSignalInfo use_prior_turn_signal(
11397
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
11498
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,

planning/behavior_path_planner_common/src/turn_signal_decider.cpp

+8-47
Original file line numberDiff line numberDiff line change
@@ -399,40 +399,6 @@ TurnIndicatorsCommand TurnSignalDecider::resolve_turn_signal(
399399
return intersection_signal_info.turn_signal;
400400
}
401401

402-
TurnSignalInfo TurnSignalDecider::overwrite_turn_signal(
403-
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
404-
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
405-
const double nearest_dist_threshold, const double nearest_yaw_threshold) const
406-
{
407-
if (original_signal.turn_signal.command == TurnIndicatorsCommand::NO_COMMAND) {
408-
return new_signal;
409-
}
410-
411-
if (original_signal.turn_signal.command == TurnIndicatorsCommand::DISABLE) {
412-
return new_signal;
413-
}
414-
415-
const auto get_distance = [&](const Pose & input_point) {
416-
const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
417-
path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold);
418-
return motion_utils::calcSignedArcLength(
419-
path.points, current_pose.position, current_seg_idx, input_point.position,
420-
nearest_seg_idx) -
421-
base_link2front_;
422-
};
423-
424-
const auto & original_desired_end_point = original_signal.desired_end_point;
425-
const auto & new_desired_start_point = new_signal.desired_start_point;
426-
427-
const double dist_to_original_desired_end = get_distance(original_desired_end_point);
428-
const double dist_to_new_desired_start = get_distance(new_desired_start_point);
429-
if (dist_to_new_desired_start > dist_to_original_desired_end) {
430-
return original_signal;
431-
}
432-
433-
return new_signal;
434-
}
435-
436402
TurnSignalInfo TurnSignalDecider::use_prior_turn_signal(
437403
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
438404
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
@@ -656,8 +622,6 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
656622
const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted,
657623
const bool override_ego_stopped_check, const bool is_pull_out) const
658624
{
659-
using tier4_autoware_utils::getPose;
660-
661625
const auto & p = parameters;
662626
const auto & rh = route_handler;
663627
const auto & ego_pose = self_odometry->pose.pose;
@@ -710,19 +674,16 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
710674

711675
const auto relative_shift_length = end_shift_length - start_shift_length;
712676

713-
const auto p_path_start = getPose(path.path.points.front());
714-
const auto p_path_end = getPose(path.path.points.back());
715-
716677
// If shift length is shorter than the threshold, it does not need to turn on blinkers
717678
if (std::fabs(relative_shift_length) < p.turn_signal_shift_length_threshold) {
718-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
679+
return std::make_pair(TurnSignalInfo{}, true);
719680
}
720681

721682
// If the vehicle does not shift anymore, we turn off the blinker
722683
if (
723684
std::fabs(end_shift_length - current_shift_length) <
724685
p.turn_signal_remaining_shift_length_threshold) {
725-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
686+
return std::make_pair(TurnSignalInfo{}, true);
726687
}
727688

728689
const auto get_command = [](const auto & shift_length) {
@@ -737,7 +698,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
737698
p.vehicle_info.max_longitudinal_offset_m;
738699

739700
if (signal_prepare_distance < ego_front_to_shift_start) {
740-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), false);
701+
return std::make_pair(TurnSignalInfo{}, false);
741702
}
742703

743704
const auto blinker_start_pose = path.path.points.at(shift_line.start_idx).point.pose;
@@ -754,13 +715,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
754715
turn_signal_info.turn_signal.command = get_command(relative_shift_length);
755716

756717
if (!p.turn_signal_on_swerving) {
757-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), false);
718+
return std::make_pair(turn_signal_info, false);
758719
}
759720

760721
lanelet::ConstLanelet lanelet;
761722
const auto query_pose = (egos_lane_is_shifted) ? shift_line.end : shift_line.start;
762723
if (!rh->getClosestLaneletWithinRoute(query_pose, &lanelet)) {
763-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
724+
return std::make_pair(TurnSignalInfo{}, true);
764725
}
765726

766727
const auto left_same_direction_lane = rh->getLeftLanelet(lanelet, true, true);
@@ -775,13 +736,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
775736
!is_pull_out && !existShiftSideLane(
776737
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
777738
p.turn_signal_shift_length_threshold)) {
778-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
739+
return std::make_pair(TurnSignalInfo{}, true);
779740
}
780741

781742
// Check if the ego will cross lane bounds.
782743
// Note that pull out requires blinkers, even if the ego does not cross lane bounds
783744
if (!is_pull_out && !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) {
784-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
745+
return std::make_pair(TurnSignalInfo{}, true);
785746
}
786747

787748
// If the ego has stopped and its close to completing its shift, turn off the blinkers
@@ -790,7 +751,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
790751
if (isNearEndOfShift(
791752
start_shift_length, end_shift_length, ego_pose.position, current_lanelets,
792753
p.turn_signal_shift_length_threshold)) {
793-
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
754+
return std::make_pair(TurnSignalInfo{}, true);
794755
}
795756
}
796757

0 commit comments

Comments
 (0)