Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(behavior_path_planner): refactor lane change turn signal info #3985

Merged
merged 4 commits into from
Jun 15, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ class LaneChangeBase

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

virtual void calcTurnSignalInfo() = 0;
virtual TurnSignalInfo calcTurnSignalInfo() = 0;

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class NormalLaneChange : public LaneChangeBase

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

void calcTurnSignalInfo() override;
TurnSignalInfo calcTurnSignalInfo() override;

bool isValidPath(const PathWithLaneId & path) const override;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ struct LaneChangePath
double acceleration{0.0};
LaneChangePhaseInfo length{};
LaneChangePhaseInfo duration{};
TurnSignalInfo turn_signal_info{};
PathWithLaneId prev_path{};
};
using LaneChangePaths = std::vector<LaneChangePath>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,9 +131,6 @@ PathWithLaneId getTargetSegment(
const double target_lane_length, const double lane_changing_length,
const double lane_changing_velocity, const double total_required_min_dist);

void get_turn_signal_info(
const LaneChangePath & lane_change_path, TurnSignalInfo * turn_signal_info);

std::vector<DrivableLanes> generateDrivableLanes(
const std::vector<DrivableLanes> original_drivable_lanes, const RouteHandler & route_handler,
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -235,22 +235,13 @@ void NormalLaneChange::resetParameters()

TurnSignalInfo NormalLaneChange::updateOutputTurnSignal()
{
calcTurnSignalInfo();
TurnSignalInfo turn_signal_info;
TurnSignalInfo turn_signal_info = calcTurnSignalInfo();
const auto [turn_signal_command, distance_to_vehicle_front] = utils::getPathTurnSignal(
status_.current_lanes, status_.lane_change_path.shifted_path,
status_.lane_change_path.shift_line, getEgoPose(), getEgoTwist().linear.x,
planner_data_->parameters);
turn_signal_info.turn_signal.command = turn_signal_command.command;

turn_signal_info.desired_start_point =
status_.lane_change_path.turn_signal_info.desired_start_point;
turn_signal_info.required_start_point =
status_.lane_change_path.turn_signal_info.required_start_point;
turn_signal_info.required_end_point =
status_.lane_change_path.turn_signal_info.required_end_point;
turn_signal_info.desired_end_point = status_.lane_change_path.turn_signal_info.desired_end_point;

return turn_signal_info;
}

Expand Down Expand Up @@ -772,7 +763,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
return safety_status;
}

void NormalLaneChange::calcTurnSignalInfo()
TurnSignalInfo NormalLaneChange::calcTurnSignalInfo()
{
const auto get_blinker_pose = [](const PathWithLaneId & path, const double length) {
double accumulated_length = 0.0;
Expand Down Expand Up @@ -819,7 +810,7 @@ void NormalLaneChange::calcTurnSignalInfo()
const auto mid_lane_change_length = path.length.lane_changing / 2;
turn_signal_info.required_end_point = get_blinker_pose(shifted_path, mid_lane_change_length);

status_.lane_change_path.turn_signal_info = turn_signal_info;
return turn_signal_info;
}

bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -590,15 +590,6 @@ ShiftLine getLaneChangingShiftLine(
return shift_line;
}

void get_turn_signal_info(
const LaneChangePath & lane_change_path, TurnSignalInfo * turn_signal_info)
{
turn_signal_info->desired_start_point = lane_change_path.turn_signal_info.desired_start_point;
turn_signal_info->required_start_point = lane_change_path.turn_signal_info.required_start_point;
turn_signal_info->required_end_point = lane_change_path.turn_signal_info.required_end_point;
turn_signal_info->desired_end_point = lane_change_path.turn_signal_info.desired_end_point;
}

std::vector<DrivableLanes> generateDrivableLanes(
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & lane_change_lanes)
Expand Down