@@ -846,7 +846,8 @@ std::vector<PullOverPath> GoalPlannerModule::sortPullOverPathCandidatesByGoalPri
846
846
847
847
std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectPullOverPath (
848
848
const std::vector<PullOverPath> & pull_over_path_candidates,
849
- const GoalCandidates & goal_candidates, const double collision_check_margin) const
849
+ const GoalCandidates & goal_candidates, const std::vector<double > & reference_path_directions,
850
+ const double collision_check_margin) const
850
851
{
851
852
for (const auto & pull_over_path : pull_over_path_candidates) {
852
853
// check if goal is safe
@@ -859,7 +860,7 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
859
860
continue ;
860
861
}
861
862
862
- if (!hasEnoughDistance (pull_over_path)) {
863
+ if (!hasEnoughDistance (pull_over_path, reference_path_directions )) {
863
864
continue ;
864
865
}
865
866
@@ -1186,8 +1187,13 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput()
1186
1187
thread_safe_data_.get_pull_over_path_candidates (), goal_candidates);
1187
1188
1188
1189
// select pull over path which is safe against static objects and get it's goal
1190
+ std::vector<double > reference_path_directions;
1191
+ for (const auto & point : getPreviousModuleOutput ().path .points ) {
1192
+ reference_path_directions.push_back (
1193
+ tf2::getYaw (tier4_autoware_utils::getPose (point).orientation ));
1194
+ }
1189
1195
const auto path_and_goal_opt = selectPullOverPath (
1190
- pull_over_path_candidates, goal_candidates,
1196
+ pull_over_path_candidates, goal_candidates, reference_path_directions,
1191
1197
parameters_->object_recognition_collision_check_hard_margins .back ());
1192
1198
1193
1199
// update thread_safe_data_
@@ -1711,7 +1717,8 @@ bool GoalPlannerModule::checkObjectsCollision(
1711
1717
return utils::path_safety_checker::checkPolygonsIntersects (ego_polygons_expanded, obj_polygons);
1712
1718
}
1713
1719
1714
- bool GoalPlannerModule::hasEnoughDistance (const PullOverPath & pull_over_path) const
1720
+ bool GoalPlannerModule::hasEnoughDistance (
1721
+ const PullOverPath & pull_over_path, const std::vector<double > & reference_path_directions) const
1715
1722
{
1716
1723
const Pose & current_pose = planner_data_->self_odometry ->pose .pose ;
1717
1724
const double current_vel = planner_data_->self_odometry ->twist .twist .linear .x ;
@@ -1721,6 +1728,23 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c
1721
1728
// so need enough distance to restart.
1722
1729
// distance to restart should be less than decide_path_distance.
1723
1730
// otherwise, the goal would change immediately after departure.
1731
+
1732
+ // reject outdated shift path on curved roads whose start pose direction is far from ego yaw
1733
+ const double pull_over_path_start_direction = tf2::getYaw (pull_over_path.start_pose .orientation );
1734
+ const bool isFollowableDirection = [&]() {
1735
+ for (const auto reference_path_direction : reference_path_directions) {
1736
+ if (
1737
+ std::fabs (tier4_autoware_utils::normalizeRadian (
1738
+ pull_over_path_start_direction - reference_path_direction)) < M_PI / 2 ) {
1739
+ return true ;
1740
+ }
1741
+ }
1742
+ return false ;
1743
+ }();
1744
+ if (!isFollowableDirection) {
1745
+ return false ;
1746
+ }
1747
+
1724
1748
const bool is_separated_path = pull_over_path.partial_paths .size () > 1 ;
1725
1749
const double distance_to_start = calcSignedArcLength (
1726
1750
pull_over_path.getFullPath ().points , current_pose.position , pull_over_path.start_pose .position );
0 commit comments