@@ -584,13 +584,6 @@ std::optional<PathWithLaneId> NormalLaneChange::extendPath()
584
584
{
585
585
universe_utils::ScopedTimeTrack st (__func__, *time_keeper_);
586
586
const auto path = status_.lane_change_path .path ;
587
- const auto lc_start_point = status_.lane_change_path .info .lane_changing_start .position ;
588
-
589
- const auto dist = calcSignedArcLength (path.points , lc_start_point, getEgoPosition ());
590
-
591
- if (dist < 0.0 ) {
592
- return std::nullopt;
593
- }
594
587
595
588
auto & target_lanes = common_data_ptr_->lanes_ptr ->target ;
596
589
const auto target_lane_length = lanelet::utils::getLaneletLength2d (target_lanes);
@@ -601,22 +594,21 @@ std::optional<PathWithLaneId> NormalLaneChange::extendPath()
601
594
if ((target_lane_length - dist_in_target.length ) > forward_path_length) {
602
595
return std::nullopt;
603
596
}
597
+ const auto dist_to_end_of_path =
598
+ lanelet::utils::getArcCoordinates (target_lanes, path.points .back ().point .pose ).length ;
604
599
605
- const auto is_goal_in_target = getRouteHandler ()->isInGoalRouteSection (target_lanes.back ());
606
-
607
- if (is_goal_in_target) {
600
+ if (common_data_ptr_->lanes_ptr ->target_lane_in_goal_section ) {
608
601
const auto goal_pose = getRouteHandler ()->getGoalPose ();
609
602
610
603
const auto dist_to_goal = lanelet::utils::getArcCoordinates (target_lanes, goal_pose).length ;
611
- const auto dist_to_end_of_path =
612
- lanelet::utils::getArcCoordinates (target_lanes, path.points .back ().point .pose ).length ;
613
604
614
605
return getRouteHandler ()->getCenterLinePath (target_lanes, dist_to_end_of_path, dist_to_goal);
615
606
}
616
607
617
608
lanelet::ConstLanelet next_lane;
618
609
if (!getRouteHandler ()->getNextLaneletWithinRoute (target_lanes.back (), &next_lane)) {
619
- return std::nullopt;
610
+ return getRouteHandler ()->getCenterLinePath (
611
+ target_lanes, dist_to_end_of_path, transient_data.target_lane_length );
620
612
}
621
613
622
614
target_lanes.push_back (next_lane);
@@ -640,8 +632,6 @@ std::optional<PathWithLaneId> NormalLaneChange::extendPath()
640
632
641
633
const auto dist_to_target_pose =
642
634
lanelet::utils::getArcCoordinates (target_lanes, target_pose).length ;
643
- const auto dist_to_end_of_path =
644
- lanelet::utils::getArcCoordinates (target_lanes, path.points .back ().point .pose ).length ;
645
635
646
636
return getRouteHandler ()->getCenterLinePath (
647
637
target_lanes, dist_to_end_of_path, dist_to_target_pose);
0 commit comments