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(lane_change): remove old architecture code #4238

Merged
merged 1 commit into from
Jul 11, 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 @@ -196,8 +196,8 @@ class LaneChangeBase
virtual int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const = 0;

virtual PathWithLaneId getPrepareSegment(
const lanelet::ConstLanelets & current_lanes, const double arc_length_from_current,
const double backward_path_length, const double prepare_length) const = 0;
const lanelet::ConstLanelets & current_lanes, const double backward_path_length,
const double prepare_length) const = 0;

virtual bool getLaneChangePaths(
const lanelet::ConstLanelets & original_lanelets,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,8 +96,8 @@ class NormalLaneChange : public LaneChangeBase
int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const override;

PathWithLaneId getPrepareSegment(
const lanelet::ConstLanelets & current_lanes, const double arc_length_from_current,
const double backward_path_length, const double prepare_length) const override;
const lanelet::ConstLanelets & current_lanes, const double backward_path_length,
const double prepare_length) const override;

bool getLaneChangePaths(
const lanelet::ConstLanelets & original_lanelets,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -466,8 +466,7 @@ int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane)
}

PathWithLaneId NormalLaneChange::getPrepareSegment(
const lanelet::ConstLanelets & current_lanes,
[[maybe_unused]] const double arc_length_from_current, const double backward_path_length,
const lanelet::ConstLanelets & current_lanes, const double backward_path_length,
const double prepare_length) const
{
if (current_lanes.empty()) {
Expand Down Expand Up @@ -538,8 +537,6 @@ bool NormalLaneChange::getLaneChangePaths(
const auto dist_to_end_of_current_lanes =
utils::getDistanceToEndOfLane(getEgoPose(), original_lanelets);

[[maybe_unused]] const auto arc_position_from_current =
lanelet::utils::getArcCoordinates(original_lanelets, getEgoPose());
const auto arc_position_from_target =
lanelet::utils::getArcCoordinates(target_lanelets, getEgoPose());

Expand Down Expand Up @@ -584,8 +581,8 @@ bool NormalLaneChange::getLaneChangePaths(
break;
}

auto prepare_segment = getPrepareSegment(
original_lanelets, arc_position_from_current.length, backward_path_length, prepare_length);
auto prepare_segment =
getPrepareSegment(original_lanelets, backward_path_length, prepare_length);

if (prepare_segment.points.empty()) {
RCLCPP_DEBUG(logger_, "prepare segment is empty!!");
Expand Down