@@ -936,6 +936,26 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
936
936
const std::vector<PullOverPath> & pull_over_path_candidates,
937
937
const GoalCandidates & goal_candidates, const double collision_check_margin) const
938
938
{
939
+ const auto & goal_pose = planner_data_->route_handler ->getOriginalGoalPose ();
940
+ const double backward_length =
941
+ parameters_->backward_goal_search_length + parameters_->decide_path_distance ;
942
+ const auto & prev_module_output_path = getPreviousModuleOutput ().path ;
943
+ const double prev_path_front_to_goal_dist = calcSignedArcLength (
944
+ prev_module_output_path.points , prev_module_output_path.points .front ().point .pose .position ,
945
+ goal_pose.position );
946
+ const auto & long_tail_reference_path = [&]() {
947
+ if (prev_path_front_to_goal_dist > backward_length) {
948
+ return prev_module_output_path;
949
+ }
950
+ // get road lanes which is at least backward_length[m] behind the goal
951
+ const auto road_lanes = utils::getExtendedCurrentLanesFromPath (
952
+ prev_module_output_path, planner_data_, backward_length, 0.0 ,
953
+ /* forward_only_in_route*/ false );
954
+ const auto goal_pose_length = lanelet::utils::getArcCoordinates (road_lanes, goal_pose).length ;
955
+ return planner_data_->route_handler ->getCenterLinePath (
956
+ road_lanes, std::max (0.0 , goal_pose_length - backward_length),
957
+ goal_pose_length + parameters_->forward_goal_search_length );
958
+ }();
939
959
for (const auto & pull_over_path : pull_over_path_candidates) {
940
960
// check if goal is safe
941
961
const auto goal_candidate_it = std::find_if (
@@ -947,7 +967,7 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
947
967
continue ;
948
968
}
949
969
950
- if (!hasEnoughDistance (pull_over_path)) {
970
+ if (!hasEnoughDistance (pull_over_path, long_tail_reference_path )) {
951
971
continue ;
952
972
}
953
973
@@ -1873,7 +1893,8 @@ bool GoalPlannerModule::checkObjectsCollision(
1873
1893
return utils::path_safety_checker::checkPolygonsIntersects (ego_polygons_expanded, obj_polygons);
1874
1894
}
1875
1895
1876
- bool GoalPlannerModule::hasEnoughDistance (const PullOverPath & pull_over_path) const
1896
+ bool GoalPlannerModule::hasEnoughDistance (
1897
+ const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const
1877
1898
{
1878
1899
const Pose & current_pose = planner_data_->self_odometry ->pose .pose ;
1879
1900
const double current_vel = planner_data_->self_odometry ->twist .twist .linear .x ;
@@ -1885,7 +1906,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c
1885
1906
// otherwise, the goal would change immediately after departure.
1886
1907
const bool is_separated_path = pull_over_path.partial_paths .size () > 1 ;
1887
1908
const double distance_to_start = calcSignedArcLength (
1888
- pull_over_path. getFullPath () .points , current_pose.position , pull_over_path.start_pose .position );
1909
+ long_tail_reference_path .points , current_pose.position , pull_over_path.start_pose .position );
1889
1910
const double distance_to_restart = parameters_->decide_path_distance / 2 ;
1890
1911
const double eps_vel = 0.01 ;
1891
1912
const bool is_stopped = std::abs (current_vel) < eps_vel;
0 commit comments