Skip to content

Commit

Permalink
refactor(goal_planner): divide sort function
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Dec 15, 2024
1 parent 5ced41e commit c7b5c87
Show file tree
Hide file tree
Showing 2 changed files with 67 additions and 49 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,12 @@ bool isStopped(
const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower,
const double velocity_upper);

void sortPullOverPaths(
const std::shared_ptr<const PlannerData> planner_data, const GoalPlannerParameters & parameters,
const std::vector<PullOverPath> & pull_over_path_candidates,
const GoalCandidates & goal_candidates, const PredictedObjects & static_target_objects,
rclcpp::Logger logger, std::vector<size_t> & sorted_path_indices);

// Flag class for managing whether a certain callback is running in multi-threading
class ScopedFlag
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -982,24 +982,14 @@ BehaviorModuleOutput GoalPlannerModule::plan()
return fixed_goal_planner_->plan(planner_data_);
}

std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
const PullOverContextData & context_data,
void sortPullOverPaths(

Check warning on line 985 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L985

Added line #L985 was not covered by tests
const std::shared_ptr<const PlannerData> planner_data, const GoalPlannerParameters & parameters,
const std::vector<PullOverPath> & pull_over_path_candidates,
const GoalCandidates & goal_candidates) const
const GoalCandidates & goal_candidates, const PredictedObjects & static_target_objects,
rclcpp::Logger logger, std::vector<size_t> & sorted_path_indices)
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);

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 auto & soft_margins = parameters_->object_recognition_collision_check_soft_margins;
const auto & hard_margins = parameters_->object_recognition_collision_check_hard_margins;

// STEP1: Filter valid paths before sorting
// NOTE: Since copying pull over path takes time, it is handled by indices
std::vector<size_t> sorted_path_indices;
sorted_path_indices.reserve(pull_over_path_candidates.size());
const auto & soft_margins = parameters.object_recognition_collision_check_soft_margins;
const auto & hard_margins = parameters.object_recognition_collision_check_hard_margins;

Check warning on line 992 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L991-L992

Added lines #L991 - L992 were not covered by tests

// STEP1-1: Extract paths which have safe goal
// Create a map of goal_id to GoalCandidate for quick access
Expand All @@ -1015,31 +1005,6 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
}
}

// STEP1-2: Remove paths which do not have enough distance
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, 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);
}();

sorted_path_indices.erase(
std::remove_if(
sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t i) {
return !hasEnoughDistance(pull_over_path_candidates[i], long_tail_reference_path);
}),
sorted_path_indices.end());

// STEP2: Sort pull over path candidates
// STEP2-1: Sort pull_over_path_candidates based on the order in goal_candidates
// Create a map of goal_id to its index in goal_candidates
Expand All @@ -1066,14 +1031,14 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(

// compare to sort pull_over_path_candidates based on the order in efficient_path_order
const auto comparePathTypePriority = [&](const PullOverPath & a, const PullOverPath & b) -> bool {
const auto & order = parameters_->efficient_path_order;
const auto & order = parameters.efficient_path_order;
const auto a_pos = std::find(order.begin(), order.end(), magic_enum::enum_name(a.type()));
const auto b_pos = std::find(order.begin(), order.end(), magic_enum::enum_name(b.type()));
return a_pos < b_pos;
};

// if object recognition is enabled, sort by collision check margin
if (parameters_->use_object_recognition) {
if (parameters.use_object_recognition) {
// STEP2-2: Sort by collision check margins
const auto [margins, margins_with_zero] =
std::invoke([&]() -> std::tuple<std::vector<double>, std::vector<double>> {
Expand All @@ -1086,11 +1051,11 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(

// Create a map of PullOverPath pointer to largest collision check margin
std::map<size_t, double> path_id_to_rough_margin_map;
const auto & target_objects = context_data.static_target_objects;
const auto & target_objects = static_target_objects;
for (const size_t i : sorted_path_indices) {
const auto & path = pull_over_path_candidates[i];
const double distance = utils::path_safety_checker::calculateRoughDistanceToObjects(
path.parking_path(), target_objects, planner_data_->parameters, false, "max");
path.parking_path(), target_objects, planner_data->parameters, false, "max");
auto it = std::lower_bound(
margins_with_zero.begin(), margins_with_zero.end(), distance, std::greater<double>());
if (it == margins_with_zero.end()) {
Expand Down Expand Up @@ -1120,7 +1085,7 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
// STEP2-3: Sort by curvature
// If the curvature is less than the threshold, prioritize the path.
const auto isHighCurvature = [&](const PullOverPath & path) -> bool {
return path.parking_path_max_curvature() >= parameters_->high_curvature_threshold;
return path.parking_path_max_curvature() >= parameters.high_curvature_threshold;
};

const auto isSoftMargin = [&](const PullOverPath & path) -> bool {
Expand Down Expand Up @@ -1156,7 +1121,7 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(

// STEP2-4: Sort pull_over_path_candidates based on the order in efficient_path_order keeping
// the collision check margin and curvature priority.
if (parameters_->path_priority == "efficient_path") {
if (parameters.path_priority == "efficient_path") {

Check notice on line 1124 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Conditional

GoalPlannerModule::selectPullOverPath no longer has a complex conditional. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.

Check notice on line 1124 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Complex Conditional

sortPullOverPaths has 2 complex conditionals with 4 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
Expand All @@ -1183,14 +1148,14 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
const std::string path_priority_info_str = goal_planner_utils::makePathPriorityDebugMessage(
sorted_path_indices, pull_over_path_candidates, goal_id_to_index, goal_candidates,
path_id_to_rough_margin_map, isSoftMargin, isHighCurvature);
RCLCPP_DEBUG_STREAM(getLogger(), path_priority_info_str);
RCLCPP_DEBUG_STREAM(logger, path_priority_info_str);
} else {
/**
* NOTE: use_object_recognition=false is not recommended. This option will be deprecated in the
* future. sort by curvature is not implemented yet.
* Sort pull_over_path_candidates based on the order in efficient_path_order
*/
if (parameters_->path_priority == "efficient_path") {
if (parameters.path_priority == "efficient_path") {
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
Expand All @@ -1203,6 +1168,53 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
});
}
}
}

Check notice on line 1171 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Complex Method

sortPullOverPaths has a cyclomatic complexity of 25, 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.

Check notice on line 1171 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Bumpy Road Ahead

sortPullOverPaths has 4 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check notice on line 1171 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Excess Number of Function Arguments

sortPullOverPaths has 7 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.

Check warning on line 1171 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1171

Added line #L1171 was not covered by tests

std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(

Check warning on line 1173 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1173

Added line #L1173 was not covered by tests
const PullOverContextData & context_data,
const std::vector<PullOverPath> & pull_over_path_candidates,
const GoalCandidates & goal_candidates) const
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);

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;

// STEP1: Filter valid paths before sorting
// NOTE: Since copying pull over path takes time, it is handled by indices
std::vector<size_t> sorted_path_indices;
sorted_path_indices.reserve(pull_over_path_candidates.size());

// STEP1-2: Remove paths which do not have enough distance
const double prev_path_front_to_goal_dist = calcSignedArcLength(

Check warning on line 1191 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1191

Added line #L1191 was not covered by tests
prev_module_output_path.points, prev_module_output_path.points.front().point.pose.position,
goal_pose.position);
const auto & long_tail_reference_path = [&]() {

Check warning on line 1194 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1193-L1194

Added lines #L1193 - L1194 were not covered by tests
if (prev_path_front_to_goal_dist > backward_length) {
return prev_module_output_path;

Check warning on line 1196 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1196

Added line #L1196 was not covered by tests
}
// 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, false);

Check warning on line 1200 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1200

Added line #L1200 was not covered by tests
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),

Check warning on line 1203 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1203

Added line #L1203 was not covered by tests
goal_pose_length + parameters_->forward_goal_search_length);
}();

sorted_path_indices.erase(
std::remove_if(

Check warning on line 1208 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1208

Added line #L1208 was not covered by tests
sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t i) {
return !hasEnoughDistance(pull_over_path_candidates[i], long_tail_reference_path);

Check warning on line 1211 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1211

Added line #L1211 was not covered by tests
}),
sorted_path_indices.end());

sortPullOverPaths(
planner_data_, *parameters_, pull_over_path_candidates, goal_candidates,
context_data.static_target_objects, getLogger(), sorted_path_indices);

Check notice on line 1217 in planning/behavior_path_planner/autoware_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 better: Complex Method

GoalPlannerModule::selectPullOverPath decreases in cyclomatic complexity from 33 to 9, 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.

Check notice on line 1217 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

GoalPlannerModule::selectPullOverPath is no longer above the threshold for logical blocks with deeply nested code. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check warning on line 1217 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1217

Added line #L1217 was not covered by tests

// STEP3: Select the final pull over path by checking collision to make it as high priority as
// possible
Expand Down

0 comments on commit c7b5c87

Please sign in to comment.