Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(goal_planner): reject candidate path whose start pose direction is not aligned with ego path #6935

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -582,7 +582,8 @@ class GoalPlannerModule : public SceneModuleInterface
void updateStatus(const BehaviorModuleOutput & output);

// validation
bool hasEnoughDistance(const PullOverPath & pull_over_path) const;
bool hasEnoughDistance(
const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const;
bool isCrossingPossible(
const lanelet::ConstLanelet & start_lane, const lanelet::ConstLanelet & end_lane) const;
bool isCrossingPossible(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1909 to 1928, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.27 to 5.28, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -936,18 +936,38 @@
const std::vector<PullOverPath> & pull_over_path_candidates,
const GoalCandidates & goal_candidates, const double collision_check_margin) const
{
const auto & goal_pose = planner_data_->route_handler->getOriginalGoalPose();
const double backward_length =
parameters_->backward_goal_search_length + parameters_->decide_path_distance;
const auto & prev_module_output_path = getPreviousModuleOutput().path;
const double prev_path_front_to_goal_dist = calcSignedArcLength(
prev_module_output_path.points, prev_module_output_path.points.front().point.pose.position,
goal_pose.position);
const auto & long_tail_reference_path = [&]() {
if (prev_path_front_to_goal_dist > backward_length) {
return prev_module_output_path;
}
// get road lanes which is at least backward_length[m] behind the goal
const auto road_lanes = utils::getExtendedCurrentLanesFromPath(
prev_module_output_path, planner_data_, backward_length, 0.0,
/*forward_only_in_route*/ false);
const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length;
return planner_data_->route_handler->getCenterLinePath(
road_lanes, std::max(0.0, goal_pose_length - backward_length),
goal_pose_length + parameters_->forward_goal_search_length);
}();
for (const auto & pull_over_path : pull_over_path_candidates) {
// check if goal is safe
const auto goal_candidate_it = std::find_if(
goal_candidates.begin(), goal_candidates.end(),
[pull_over_path](const auto & goal_candidate) {
return goal_candidate.id == pull_over_path.goal_id;
});
if (goal_candidate_it != goal_candidates.end() && !goal_candidate_it->is_safe) {
continue;
}

if (!hasEnoughDistance(pull_over_path)) {
if (!hasEnoughDistance(pull_over_path, long_tail_reference_path)) {

Check warning on line 970 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

GoalPlannerModule::selectPullOverPath increases in cyclomatic complexity from 13 to 14, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
continue;
}

Expand Down Expand Up @@ -1873,7 +1893,8 @@
return utils::path_safety_checker::checkPolygonsIntersects(ego_polygons_expanded, obj_polygons);
}

bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) const
bool GoalPlannerModule::hasEnoughDistance(
const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const
{
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
const double current_vel = planner_data_->self_odometry->twist.twist.linear.x;
Expand All @@ -1885,7 +1906,7 @@
// otherwise, the goal would change immediately after departure.
const bool is_separated_path = pull_over_path.partial_paths.size() > 1;
const double distance_to_start = calcSignedArcLength(
pull_over_path.getFullPath().points, current_pose.position, pull_over_path.start_pose.position);
long_tail_reference_path.points, current_pose.position, pull_over_path.start_pose.position);
const double distance_to_restart = parameters_->decide_path_distance / 2;
const double eps_vel = 0.01;
const bool is_stopped = std::abs(current_vel) < eps_vel;
Expand Down
Loading