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

fix(lane_change): extending lane change path for multiple lane change (RT1-8427) (#9268) #1656

Open
wants to merge 1 commit into
base: beta/v0.36
Choose a base branch
from
Open
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 @@ -584,13 +584,6 @@ std::optional<PathWithLaneId> NormalLaneChange::extendPath()
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
const auto path = status_.lane_change_path.path;
const auto lc_start_point = status_.lane_change_path.info.lane_changing_start.position;

const auto dist = calcSignedArcLength(path.points, lc_start_point, getEgoPosition());

if (dist < 0.0) {
return std::nullopt;
}

auto & target_lanes = common_data_ptr_->lanes_ptr->target;
const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes);
Expand All @@ -601,22 +594,21 @@ std::optional<PathWithLaneId> NormalLaneChange::extendPath()
if ((target_lane_length - dist_in_target.length) > forward_path_length) {
return std::nullopt;
}
const auto dist_to_end_of_path =
lanelet::utils::getArcCoordinates(target_lanes, path.points.back().point.pose).length;

const auto is_goal_in_target = getRouteHandler()->isInGoalRouteSection(target_lanes.back());

if (is_goal_in_target) {
if (common_data_ptr_->lanes_ptr->target_lane_in_goal_section) {
const auto goal_pose = getRouteHandler()->getGoalPose();

const auto dist_to_goal = lanelet::utils::getArcCoordinates(target_lanes, goal_pose).length;
const auto dist_to_end_of_path =
lanelet::utils::getArcCoordinates(target_lanes, path.points.back().point.pose).length;

return getRouteHandler()->getCenterLinePath(target_lanes, dist_to_end_of_path, dist_to_goal);
}

lanelet::ConstLanelet next_lane;
if (!getRouteHandler()->getNextLaneletWithinRoute(target_lanes.back(), &next_lane)) {
return std::nullopt;
return getRouteHandler()->getCenterLinePath(
target_lanes, dist_to_end_of_path, transient_data.target_lane_length);
}

target_lanes.push_back(next_lane);
Expand All @@ -640,8 +632,6 @@ std::optional<PathWithLaneId> NormalLaneChange::extendPath()

const auto dist_to_target_pose =
lanelet::utils::getArcCoordinates(target_lanes, target_pose).length;
const auto dist_to_end_of_path =
lanelet::utils::getArcCoordinates(target_lanes, path.points.back().point.pose).length;

return getRouteHandler()->getCenterLinePath(
target_lanes, dist_to_end_of_path, dist_to_target_pose);
Expand Down
Loading