Skip to content

Commit a742e82

Browse files
fix(turn_signal, lane_change, goal_planner): add optional to tackle lane change turn signal and pull over turn signal (#8463)
* add optional to tackle LC turn signal and pull over turn signal Signed-off-by: YuxuanLiuTier4Desktop <619684051@qq.com> * CPP file should not re-define default value; typo in copying from internal repos Signed-off-by: YuxuanLiuTier4Desktop <619684051@qq.com> --------- Signed-off-by: YuxuanLiuTier4Desktop <619684051@qq.com>
1 parent 93b9a5b commit a742e82

File tree

5 files changed

+20
-10
lines changed

5 files changed

+20
-10
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -1957,6 +1957,8 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo()
19571957
constexpr bool is_driving_forward = true;
19581958

19591959
constexpr bool is_pull_out = false;
1960+
constexpr bool is_lane_change = false;
1961+
constexpr bool is_pull_over = true;
19601962
const bool override_ego_stopped_check = std::invoke([&]() {
19611963
if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::SHIFT) {
19621964
return false;
@@ -1972,7 +1974,7 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo()
19721974

19731975
const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo(
19741976
path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length, is_driving_forward,
1975-
egos_lane_is_shifted, override_ego_stopped_check, is_pull_out);
1977+
egos_lane_is_shifted, override_ego_stopped_check, is_pull_out, is_lane_change, is_pull_over);
19761978
ignore_signal_ = update_ignore_signal(closest_lanelet.id(), is_ignore);
19771979

19781980
return new_signal;

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -603,10 +603,12 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const
603603
// The getBehaviorTurnSignalInfo method expects the shifted line to be generated off of the ego's
604604
// current lane, lane change is different, so we set this flag to false.
605605
constexpr bool egos_lane_is_shifted = false;
606+
constexpr bool is_pull_out = false;
607+
constexpr bool is_lane_change = true;
606608

607609
const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo(
608610
shift_path, shift_line, current_lanes, current_shift_length, is_driving_forward,
609-
egos_lane_is_shifted);
611+
egos_lane_is_shifted, is_pull_out, is_lane_change);
610612
return new_signal;
611613
}
612614

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,8 @@ struct PlannerData
174174
const PathWithLaneId & path, const size_t shift_start_idx, const size_t shift_end_idx,
175175
const lanelet::ConstLanelets & current_lanelets, const double current_shift_length,
176176
const bool is_driving_forward, const bool egos_lane_is_shifted,
177-
const bool override_ego_stopped_check = false, const bool is_pull_out = false) const
177+
const bool override_ego_stopped_check = false, const bool is_pull_out = false,
178+
const bool is_lane_change = false, const bool is_pull_over = false) const
178179
{
179180
if (shift_start_idx + 1 > path.points.size()) {
180181
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
@@ -211,7 +212,7 @@ struct PlannerData
211212
return turn_signal_decider.getBehaviorTurnSignalInfo(
212213
shifted_path, shift_line, current_lanelets, route_handler, parameters, self_odometry,
213214
current_shift_length, is_driving_forward, egos_lane_is_shifted, override_ego_stopped_check,
214-
is_pull_out);
215+
is_pull_out, is_lane_change, is_pull_over);
215216
}
216217

217218
std::pair<TurnSignalInfo, bool> getBehaviorTurnSignalInfo(

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,8 @@ class TurnSignalDecider
134134
const BehaviorPathPlannerParameters & parameters, const Odometry::ConstSharedPtr self_odometry,
135135
const double current_shift_length, const bool is_driving_forward,
136136
const bool egos_lane_is_shifted, const bool override_ego_stopped_check = false,
137-
const bool is_pull_out = false) const;
137+
const bool is_pull_out = false, const bool is_lane_change = false,
138+
const bool is_pull_over = false) const;
138139

139140
private:
140141
std::optional<TurnSignalInfo> getIntersectionTurnSignalInfo(

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp

+9-5
Original file line numberDiff line numberDiff line change
@@ -652,7 +652,8 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
652652
const std::shared_ptr<RouteHandler> route_handler,
653653
const BehaviorPathPlannerParameters & parameters, const Odometry::ConstSharedPtr self_odometry,
654654
const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted,
655-
const bool override_ego_stopped_check, const bool is_pull_out) const
655+
const bool override_ego_stopped_check, const bool is_pull_out, const bool is_lane_change,
656+
const bool is_pull_over) const
656657
{
657658
using autoware::universe_utils::getPose;
658659

@@ -770,15 +771,18 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
770771
right_same_direction_lane.has_value() || !right_opposite_lanes.empty();
771772

772773
if (
773-
!is_pull_out && !existShiftSideLane(
774-
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
775-
p.turn_signal_shift_length_threshold)) {
774+
(!is_pull_out && !is_lane_change && !is_pull_over) &&
775+
!existShiftSideLane(
776+
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
777+
p.turn_signal_shift_length_threshold)) {
776778
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
777779
}
778780

779781
// Check if the ego will cross lane bounds.
780782
// Note that pull out requires blinkers, even if the ego does not cross lane bounds
781-
if (!is_pull_out && !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) {
783+
if (
784+
(!is_pull_out && !is_pull_over) &&
785+
!straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) {
782786
return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true);
783787
}
784788

0 commit comments

Comments
 (0)