Skip to content

Commit bcc93c1

Browse files
authoredJun 15, 2023
refactor(behavior_path_planner): refactor lane change turn signal info (#3985)
* feat(behavior_path_planner): add a length ratio parameter for lane change turn signal deactivation Signed-off-by: yutaka <purewater0901@gmail.com> * add guard Signed-off-by: yutaka <purewater0901@gmail.com> * refactor(behavior_path_planner): refactor lane change turn signal info Signed-off-by: yutaka <purewater0901@gmail.com> --------- Signed-off-by: yutaka <purewater0901@gmail.com>
1 parent 28af5f7 commit bcc93c1

File tree

6 files changed

+5
-27
lines changed

6 files changed

+5
-27
lines changed
 

‎planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -199,7 +199,7 @@ class LaneChangeBase
199199

200200
virtual std::vector<DrivableLanes> getDrivableLanes() const = 0;
201201

202-
virtual void calcTurnSignalInfo() = 0;
202+
virtual TurnSignalInfo calcTurnSignalInfo() = 0;
203203

204204
virtual bool isValidPath(const PathWithLaneId & path) const = 0;
205205

‎planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ class NormalLaneChange : public LaneChangeBase
102102

103103
std::vector<DrivableLanes> getDrivableLanes() const override;
104104

105-
void calcTurnSignalInfo() override;
105+
TurnSignalInfo calcTurnSignalInfo() override;
106106

107107
bool isValidPath(const PathWithLaneId & path) const override;
108108
};

‎planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,6 @@ struct LaneChangePath
3939
double acceleration{0.0};
4040
LaneChangePhaseInfo length{};
4141
LaneChangePhaseInfo duration{};
42-
TurnSignalInfo turn_signal_info{};
4342
PathWithLaneId prev_path{};
4443
};
4544
using LaneChangePaths = std::vector<LaneChangePath>;

‎planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -131,9 +131,6 @@ PathWithLaneId getTargetSegment(
131131
const double target_lane_length, const double lane_changing_length,
132132
const double lane_changing_velocity, const double total_required_min_dist);
133133

134-
void get_turn_signal_info(
135-
const LaneChangePath & lane_change_path, TurnSignalInfo * turn_signal_info);
136-
137134
std::vector<DrivableLanes> generateDrivableLanes(
138135
const std::vector<DrivableLanes> original_drivable_lanes, const RouteHandler & route_handler,
139136
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes);

‎planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp

+3-12
Original file line numberDiff line numberDiff line change
@@ -235,22 +235,13 @@ void NormalLaneChange::resetParameters()
235235

236236
TurnSignalInfo NormalLaneChange::updateOutputTurnSignal()
237237
{
238-
calcTurnSignalInfo();
239-
TurnSignalInfo turn_signal_info;
238+
TurnSignalInfo turn_signal_info = calcTurnSignalInfo();
240239
const auto [turn_signal_command, distance_to_vehicle_front] = utils::getPathTurnSignal(
241240
status_.current_lanes, status_.lane_change_path.shifted_path,
242241
status_.lane_change_path.shift_line, getEgoPose(), getEgoTwist().linear.x,
243242
planner_data_->parameters);
244243
turn_signal_info.turn_signal.command = turn_signal_command.command;
245244

246-
turn_signal_info.desired_start_point =
247-
status_.lane_change_path.turn_signal_info.desired_start_point;
248-
turn_signal_info.required_start_point =
249-
status_.lane_change_path.turn_signal_info.required_start_point;
250-
turn_signal_info.required_end_point =
251-
status_.lane_change_path.turn_signal_info.required_end_point;
252-
turn_signal_info.desired_end_point = status_.lane_change_path.turn_signal_info.desired_end_point;
253-
254245
return turn_signal_info;
255246
}
256247

@@ -772,7 +763,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
772763
return safety_status;
773764
}
774765

775-
void NormalLaneChange::calcTurnSignalInfo()
766+
TurnSignalInfo NormalLaneChange::calcTurnSignalInfo()
776767
{
777768
const auto get_blinker_pose = [](const PathWithLaneId & path, const double length) {
778769
double accumulated_length = 0.0;
@@ -819,7 +810,7 @@ void NormalLaneChange::calcTurnSignalInfo()
819810
const auto mid_lane_change_length = path.length.lane_changing / 2;
820811
turn_signal_info.required_end_point = get_blinker_pose(shifted_path, mid_lane_change_length);
821812

822-
status_.lane_change_path.turn_signal_info = turn_signal_info;
813+
return turn_signal_info;
823814
}
824815

825816
bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const

‎planning/behavior_path_planner/src/utils/lane_change/utils.cpp

-9
Original file line numberDiff line numberDiff line change
@@ -590,15 +590,6 @@ ShiftLine getLaneChangingShiftLine(
590590
return shift_line;
591591
}
592592

593-
void get_turn_signal_info(
594-
const LaneChangePath & lane_change_path, TurnSignalInfo * turn_signal_info)
595-
{
596-
turn_signal_info->desired_start_point = lane_change_path.turn_signal_info.desired_start_point;
597-
turn_signal_info->required_start_point = lane_change_path.turn_signal_info.required_start_point;
598-
turn_signal_info->required_end_point = lane_change_path.turn_signal_info.required_end_point;
599-
turn_signal_info->desired_end_point = lane_change_path.turn_signal_info.desired_end_point;
600-
}
601-
602593
std::vector<DrivableLanes> generateDrivableLanes(
603594
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
604595
const lanelet::ConstLanelets & lane_change_lanes)

0 commit comments

Comments
 (0)
Please sign in to comment.