Skip to content

Commit e8c1d2b

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

File tree

2 files changed

+26
-4
lines changed

2 files changed

+26
-4
lines changed

planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -497,7 +497,8 @@ class GoalPlannerModule : public SceneModuleInterface
497497
void updateStatus(const BehaviorModuleOutput & output);
498498

499499
// validation
500-
bool hasEnoughDistance(const PullOverPath & pull_over_path) const;
500+
bool hasEnoughDistance(
501+
const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const;
501502
bool isCrossingPossible(
502503
const lanelet::ConstLanelet & start_lane, const lanelet::ConstLanelet & end_lane) const;
503504
bool isCrossingPossible(

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

+24-3
Original file line numberDiff line numberDiff line change
@@ -778,6 +778,26 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
778778
const std::vector<PullOverPath> & pull_over_path_candidates,
779779
const GoalCandidates & goal_candidates, const double collision_check_margin) const
780780
{
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+
}();
781801
for (const auto & pull_over_path : pull_over_path_candidates) {
782802
// check if goal is safe
783803
const auto goal_candidate_it = std::find_if(
@@ -789,7 +809,7 @@ std::optional<std::pair<PullOverPath, GoalCandidate>> GoalPlannerModule::selectP
789809
continue;
790810
}
791811

792-
if (!hasEnoughDistance(pull_over_path)) {
812+
if (!hasEnoughDistance(pull_over_path, long_tail_reference_path)) {
793813
continue;
794814
}
795815

@@ -1610,7 +1630,8 @@ bool GoalPlannerModule::checkObjectsCollision(
16101630
return utils::path_safety_checker::checkPolygonsIntersects(ego_polygons_expanded, obj_polygons);
16111631
}
16121632

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
16141635
{
16151636
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
16161637
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
16221643
// otherwise, the goal would change immediately after departure.
16231644
const bool is_separated_path = pull_over_path.partial_paths.size() > 1;
16241645
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);
16261647
const double distance_to_restart = parameters_->decide_path_distance / 2;
16271648
const double eps_vel = 0.01;
16281649
const bool is_stopped = std::abs(current_vel) < eps_vel;

0 commit comments

Comments
 (0)