@@ -778,6 +778,26 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
778
778
const std::vector<PullOverPath> & pull_over_path_candidates,
779
779
const GoalCandidates & goal_candidates, const double collision_check_margin) const
780
780
{
781
+ const auto & goal_pose = planner_data_->route_handler ->getOriginalGoalPose ();
782
+ const double backward_length =
783
+ parameters_->backward_goal_search_length + parameters_->decide_path_distance ;
784
+ const auto & prev_module_output_path = getPreviousModuleOutput ().path ;
785
+ const double prev_path_front_to_goal_dist = calcSignedArcLength (
786
+ prev_module_output_path.points , prev_module_output_path.points .front ().point .pose .position ,
787
+ goal_pose.position );
788
+ const auto & long_tail_reference_path = [&]() {
789
+ if (prev_path_front_to_goal_dist > backward_length) {
790
+ return prev_module_output_path;
791
+ }
792
+ // get road lanes which is at least backward_length[m] behind the goal
793
+ const auto road_lanes = utils::getExtendedCurrentLanesFromPath (
794
+ prev_module_output_path, planner_data_, backward_length, 0.0 ,
795
+ /* forward_only_in_route*/ false );
796
+ const auto goal_pose_length = lanelet::utils::getArcCoordinates (road_lanes, goal_pose).length ;
797
+ return planner_data_->route_handler ->getCenterLinePath (
798
+ road_lanes, std::max (0.0 , goal_pose_length - backward_length),
799
+ goal_pose_length + parameters_->forward_goal_search_length );
800
+ }();
781
801
for (const auto & pull_over_path : pull_over_path_candidates) {
782
802
// check if goal is safe
783
803
const auto goal_candidate_it = std::find_if (
@@ -789,7 +809,7 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
789
809
continue ;
790
810
}
791
811
792
- if (!hasEnoughDistance (pull_over_path)) {
812
+ if (!hasEnoughDistance (pull_over_path, long_tail_reference_path )) {
793
813
continue ;
794
814
}
795
815
@@ -1610,7 +1630,8 @@ bool GoalPlannerModule::checkObjectsCollision(
1610
1630
return utils::path_safety_checker::checkPolygonsIntersects (ego_polygons_expanded, obj_polygons);
1611
1631
}
1612
1632
1613
- bool GoalPlannerModule::hasEnoughDistance (const PullOverPath & pull_over_path) const
1633
+ bool GoalPlannerModule::hasEnoughDistance (
1634
+ const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const
1614
1635
{
1615
1636
const Pose & current_pose = planner_data_->self_odometry ->pose .pose ;
1616
1637
const double current_vel = planner_data_->self_odometry ->twist .twist .linear .x ;
@@ -1622,7 +1643,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c
1622
1643
// otherwise, the goal would change immediately after departure.
1623
1644
const bool is_separated_path = pull_over_path.partial_paths .size () > 1 ;
1624
1645
const double distance_to_start = calcSignedArcLength (
1625
- pull_over_path. getFullPath () .points , current_pose.position , pull_over_path.start_pose .position );
1646
+ long_tail_reference_path .points , current_pose.position , pull_over_path.start_pose .position );
1626
1647
const double distance_to_restart = parameters_->decide_path_distance / 2 ;
1627
1648
const double eps_vel = 0.01 ;
1628
1649
const bool is_stopped = std::abs (current_vel) < eps_vel;
0 commit comments