Skip to content

Commit 1fc0411

Browse files
committed
feat(goal_planner): reject candidate path whose start pose direction is not aligned with ego path
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 985b735 commit 1fc0411

File tree

2 files changed

+33
-6
lines changed

2 files changed

+33
-6
lines changed

planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -499,7 +499,9 @@ class GoalPlannerModule : public SceneModuleInterface
499499
void updateStatus(const BehaviorModuleOutput & output);
500500

501501
// validation
502-
bool hasEnoughDistance(const PullOverPath & pull_over_path) const;
502+
bool hasEnoughDistance(
503+
const PullOverPath & pull_over_path,
504+
const std::vector<double> & reference_path_directions) const;
503505
bool isCrossingPossible(
504506
const lanelet::ConstLanelet & start_lane, const lanelet::ConstLanelet & end_lane) const;
505507
bool isCrossingPossible(
@@ -517,7 +519,8 @@ class GoalPlannerModule : public SceneModuleInterface
517519
BehaviorModuleOutput planPullOverAsCandidate();
518520
std::optional<std::pair<PullOverPath, GoalCandidate>> selectPullOverPath(
519521
const std::vector<PullOverPath> & pull_over_path_candidates,
520-
const GoalCandidates & goal_candidates, const double collision_check_margin) const;
522+
const GoalCandidates & goal_candidates, const std::vector<double> & reference_path_directions,
523+
const double collision_check_margin) const;
521524
std::vector<PullOverPath> sortPullOverPathCandidatesByGoalPriority(
522525
const std::vector<PullOverPath> & pull_over_path_candidates,
523526
const GoalCandidates & goal_candidates) const;

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

+28-4
Original file line numberDiff line numberDiff line change
@@ -846,7 +846,8 @@ std::vector<PullOverPath> GoalPlannerModule::sortPullOverPathCandidatesByGoalPri
846846

847847
std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectPullOverPath(
848848
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
850851
{
851852
for (const auto & pull_over_path : pull_over_path_candidates) {
852853
// check if goal is safe
@@ -859,7 +860,7 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
859860
continue;
860861
}
861862

862-
if (!hasEnoughDistance(pull_over_path)) {
863+
if (!hasEnoughDistance(pull_over_path, reference_path_directions)) {
863864
continue;
864865
}
865866

@@ -1186,8 +1187,13 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput()
11861187
thread_safe_data_.get_pull_over_path_candidates(), goal_candidates);
11871188

11881189
// 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+
}
11891195
const auto path_and_goal_opt = selectPullOverPath(
1190-
pull_over_path_candidates, goal_candidates,
1196+
pull_over_path_candidates, goal_candidates, reference_path_directions,
11911197
parameters_->object_recognition_collision_check_hard_margins.back());
11921198

11931199
// update thread_safe_data_
@@ -1711,7 +1717,8 @@ bool GoalPlannerModule::checkObjectsCollision(
17111717
return utils::path_safety_checker::checkPolygonsIntersects(ego_polygons_expanded, obj_polygons);
17121718
}
17131719

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
17151722
{
17161723
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
17171724
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
17211728
// so need enough distance to restart.
17221729
// distance to restart should be less than decide_path_distance.
17231730
// 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+
17241748
const bool is_separated_path = pull_over_path.partial_paths.size() > 1;
17251749
const double distance_to_start = calcSignedArcLength(
17261750
pull_over_path.getFullPath().points, current_pose.position, pull_over_path.start_pose.position);

0 commit comments

Comments
 (0)