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

refactor(goal_planner): remove use_object_recognition because it is default #10050

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 @@ -39,7 +39,6 @@

# object recognition
object_recognition:
use_object_recognition: true
collision_check_soft_margins: [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0] # the maximum margin when ego and objects are oriented.
collision_check_hard_margins: [0.6] # this should be larger than `surround_check_distance` of surround_obstacle_checker
object_recognition_collision_check_max_extra_stopping_margin: 1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,6 @@ struct GoalPlannerParameters
int obstacle_threshold{0};

// object recognition
bool use_object_recognition{false};
std::vector<double> object_recognition_collision_check_soft_margins{};
std::vector<double> object_recognition_collision_check_hard_margins{};
double object_recognition_collision_check_max_extra_stopping_margin{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,16 +175,13 @@

// if object recognition for path collision check is enabled, transition to DECIDING to check
// collision for a certain period of time. Otherwise, transition to DECIDED directly.
if (parameters.use_object_recognition) {
RCLCPP_DEBUG(
logger_,
"[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain "
"period of time");
next_state.state = PathDecisionState::DecisionKind::DECIDING;
next_state.deciding_start_time = now;
return next_state;
}
return {PathDecisionState::DecisionKind::DECIDED, std::nullopt};
RCLCPP_DEBUG(
logger_,
"[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain "
"period of time");
next_state.state = PathDecisionState::DecisionKind::DECIDING;

Check warning on line 182 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp#L182

Added line #L182 was not covered by tests
next_state.deciding_start_time = now;
return next_state;

Check notice on line 184 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

PathDecisionStateController::get_next_state decreases in cyclomatic complexity from 19 to 18, 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.
}

} // namespace autoware::behavior_path_planner
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_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: Lines of Code in a Single File

The lines of code decreases from 1925 to 1905, 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_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: Overall Code Complexity

The mean cyclomatic complexity decreases from 6.59 to 6.48, 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 @@ -971,14 +971,13 @@

const auto & path = lane_parking_path.full_path();
const auto & curvatures = lane_parking_path.full_path_curvatures();
if (
parameters_.use_object_recognition &&
goal_planner_utils::checkObjectsCollision(
path, curvatures, context_data.static_target_objects, context_data.dynamic_target_objects,
planner_data_->parameters, parameters_.object_recognition_collision_check_hard_margins.back(),
/*extract_static_objects=*/false, parameters_.maximum_deceleration,
parameters_.object_recognition_collision_check_max_extra_stopping_margin,
debug_data_.ego_polygons_expanded)) {
if (goal_planner_utils::checkObjectsCollision(
path, curvatures, context_data.static_target_objects, context_data.dynamic_target_objects,
planner_data_->parameters,

Check warning on line 976 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#L975-L976

Added lines #L975 - L976 were not covered by tests
parameters_.object_recognition_collision_check_hard_margins.back(),
/*extract_static_objects=*/false, parameters_.maximum_deceleration,
parameters_.object_recognition_collision_check_max_extra_stopping_margin,
debug_data_.ego_polygons_expanded)) {

Check notice on line 980 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 Method

GoalPlannerModule::canReturnToLaneParking is no longer above the threshold for cyclomatic complexity. 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 warning on line 980 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#L978-L980

Added lines #L978 - L980 were not covered by tests
return false;
}

Expand Down Expand Up @@ -1082,136 +1081,116 @@
};

// if object recognition is enabled, sort by collision check margin
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>> {
std::vector<double> margins = soft_margins;
margins.insert(margins.end(), hard_margins.begin(), hard_margins.end());
std::vector<double> margins_with_zero = margins;
margins_with_zero.push_back(0.0);
return std::make_tuple(margins, margins_with_zero);
});
// STEP2-2: Sort by collision check margins
const auto [margins, margins_with_zero] =
std::invoke([&]() -> std::tuple<std::vector<double>, std::vector<double>> {
std::vector<double> margins = soft_margins;

Check warning on line 1087 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#L1086-L1087

Added lines #L1086 - L1087 were not covered by tests
margins.insert(margins.end(), hard_margins.begin(), hard_margins.end());
std::vector<double> margins_with_zero = margins;
margins_with_zero.push_back(0.0);
return std::make_tuple(margins, margins_with_zero);

Check warning on line 1091 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#L1091

Added line #L1091 was not covered by tests
});

// 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 = 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");
auto it = std::lower_bound(
margins_with_zero.begin(), margins_with_zero.end(), distance, std::greater<double>());
if (it == margins_with_zero.end()) {
path_id_to_rough_margin_map[path.id()] = margins_with_zero.back();
} else {
path_id_to_rough_margin_map[path.id()] = *it;
}
// 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 = 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");
auto it = std::lower_bound(
margins_with_zero.begin(), margins_with_zero.end(), distance, std::greater<double>());
if (it == margins_with_zero.end()) {
path_id_to_rough_margin_map[path.id()] = margins_with_zero.back();
} else {
path_id_to_rough_margin_map[path.id()] = *it;
}
}

// sorts in descending order so the item with larger margin comes first
std::stable_sort(
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
if (!isSameNumObjectsToAvoid(a, b)) {
return false;
}
if (
std::abs(path_id_to_rough_margin_map[a.id()] - path_id_to_rough_margin_map[b.id()]) <
0.01) {
return false;
}
return path_id_to_rough_margin_map[a.id()] > path_id_to_rough_margin_map[b.id()];
});
// sorts in descending order so the item with larger margin comes first
std::stable_sort(
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];

Check warning on line 1114 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#L1113-L1114

Added lines #L1113 - L1114 were not covered by tests
const auto & b = pull_over_path_candidates[b_i];
if (!isSameNumObjectsToAvoid(a, b)) {
return false;
}
if (
std::abs(path_id_to_rough_margin_map[a.id()] - path_id_to_rough_margin_map[b.id()]) <
0.01) {
return false;
}
return path_id_to_rough_margin_map[a.id()] > path_id_to_rough_margin_map[b.id()];

Check warning 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

Codecov / codecov/patch

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

Added line #L1124 was not covered by tests
});

// 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;
};

Check warning on line 1131 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#L1131

Added line #L1131 was not covered by tests

const auto isSoftMargin = [&](const PullOverPath & path) -> bool {
const double margin = path_id_to_rough_margin_map[path.id()];

Check warning on line 1134 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#L1133-L1134

Added lines #L1133 - L1134 were not covered by tests
return std::any_of(
soft_margins.begin(), soft_margins.end(),

Check warning on line 1136 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#L1136

Added line #L1136 was not covered by tests
[margin](const double soft_margin) { return std::abs(margin - soft_margin) < 0.01; });
};
const auto isSameHardMargin = [&](const PullOverPath & a, const PullOverPath & b) -> bool {

Check warning on line 1139 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#L1138-L1139

Added lines #L1138 - L1139 were not covered by tests
return !isSoftMargin(a) && !isSoftMargin(b) &&
std::abs(path_id_to_rough_margin_map[a.id()] - path_id_to_rough_margin_map[b.id()]) <
0.01;
};

Check warning on line 1143 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#L1142-L1143

Added lines #L1142 - L1143 were not covered by tests

// 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;
};

const auto isSoftMargin = [&](const PullOverPath & path) -> bool {
const double margin = path_id_to_rough_margin_map[path.id()];
return std::any_of(
soft_margins.begin(), soft_margins.end(),
[margin](const double soft_margin) { return std::abs(margin - soft_margin) < 0.01; });
};
const auto isSameHardMargin = [&](const PullOverPath & a, const PullOverPath & b) -> bool {
return !isSoftMargin(a) && !isSoftMargin(b) &&
std::abs(path_id_to_rough_margin_map[a.id()] - path_id_to_rough_margin_map[b.id()]) <
0.01;
};

// NOTE: this is just partition sort based on curvature threshold within each sub partitions
// NOTE: this is just partition sort based on curvature threshold within each sub partitions
std::stable_sort(
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];

Check warning on line 1149 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#L1148-L1149

Added lines #L1148 - L1149 were not covered by tests
const auto & b = pull_over_path_candidates[b_i];
if (!isSameNumObjectsToAvoid(a, b)) {
return false;
}

// if both are soft margin or both are same hard margin, prioritize the path with lower
// curvature.
if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) {
return !isHighCurvature(a) && isHighCurvature(b);
}
// otherwise, keep the order based on the margin.
return false;
});

// 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") {
std::stable_sort(
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
// if any of following conditions are met, sort by path type priority
// - both are soft margin
// - both are same hard margin
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
if (!isSameNumObjectsToAvoid(a, b)) {
return false;
}

// if both are soft margin or both are same hard margin, prioritize the path with lower
// curvature.
if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) {
return !isHighCurvature(a) && isHighCurvature(b);
return comparePathTypePriority(a, b);

Check warning on line 1179 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#L1179

Added line #L1179 was not covered by tests
}
// otherwise, keep the order based on the margin.
// otherwise, keep the order.
return false;
});

// 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") {
std::stable_sort(
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
// if any of following conditions are met, sort by path type priority
// - both are soft margin
// - both are same hard margin
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
if (!isSameNumObjectsToAvoid(a, b)) {
return false;
}
if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) {
return comparePathTypePriority(a, b);
}
// otherwise, keep the order.
return false;
});
}

// debug print path priority sorted by
// - efficient_path_order
// - collision check margin
// - curvature
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(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") {
std::stable_sort(
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
if (!isSameNumObjectsToAvoid(a, b)) {
return false;
}
return comparePathTypePriority(a, b);
});
}
}

// debug print path priority sorted by
// - efficient_path_order
// - collision check margin
// - curvature
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(logger, path_priority_info_str);

Check notice on line 1193 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

sortPullOverPaths decreases in cyclomatic complexity from 21 to 18, 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 1193 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: Bumpy Road Ahead

sortPullOverPaths decreases from 3 to 2 logical blocks with deeply nested code, threshold is one single 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.
}

std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
Expand Down Expand Up @@ -1285,14 +1264,12 @@
const auto & path = pull_over_path_candidates[i];
const PathWithLaneId & parking_path = path.parking_path();
const auto & parking_path_curvatures = path.parking_path_curvatures();
if (
parameters_.use_object_recognition &&
goal_planner_utils::checkObjectsCollision(
parking_path, parking_path_curvatures, context_data.static_target_objects,
context_data.dynamic_target_objects, planner_data_->parameters, collision_check_margin,
true, parameters_.maximum_deceleration,
parameters_.object_recognition_collision_check_max_extra_stopping_margin,
debug_data_.ego_polygons_expanded, true)) {
if (goal_planner_utils::checkObjectsCollision(
parking_path, parking_path_curvatures, context_data.static_target_objects,
context_data.dynamic_target_objects, planner_data_->parameters, collision_check_margin,
true, parameters_.maximum_deceleration,
parameters_.object_recognition_collision_check_max_extra_stopping_margin,

Check warning on line 1271 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#L1270-L1271

Added lines #L1270 - L1271 were not covered by tests
debug_data_.ego_polygons_expanded, true)) {

Check notice on line 1272 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 14 to 13, 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;
}
if (
Expand Down Expand Up @@ -1859,18 +1836,16 @@
return true;
}

if (parameters.use_object_recognition) {
const auto & path = req.get_pull_over_path().value().getCurrentPath();
const auto curvatures = autoware::motion_utils::calcCurvature(path.points);
std::vector<Polygon2d> ego_polygons_expanded;
if (goal_planner_utils::checkObjectsCollision(
path, curvatures, static_target_objects, dynamic_target_objects, planner_data->parameters,
parameters.object_recognition_collision_check_hard_margins.back(),
/*extract_static_objects=*/false, parameters.maximum_deceleration,
parameters.object_recognition_collision_check_max_extra_stopping_margin,
ego_polygons_expanded)) {
return true;
}
const auto & path = req.get_pull_over_path().value().getCurrentPath();
const auto curvatures = autoware::motion_utils::calcCurvature(path.points);

Check warning on line 1840 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#L1839-L1840

Added lines #L1839 - L1840 were not covered by tests
std::vector<Polygon2d> ego_polygons_expanded;
if (goal_planner_utils::checkObjectsCollision(
path, curvatures, static_target_objects, dynamic_target_objects, planner_data->parameters,
parameters.object_recognition_collision_check_hard_margins.back(),
/*extract_static_objects=*/false, parameters.maximum_deceleration,

Check warning on line 1845 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#L1845

Added line #L1845 was not covered by tests
parameters.object_recognition_collision_check_max_extra_stopping_margin,
ego_polygons_expanded)) {
return true;

Check notice on line 1848 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 Method

FreespaceParkingPlanner::isStuck is no longer above the threshold for cyclomatic complexity. 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.
}

if (
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 5.64 to 5.57, 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 @@ -444,12 +444,10 @@
}
}

if (parameters_.use_object_recognition) {
if (utils::checkCollisionBetweenFootprintAndObjects(
vehicle_footprint_, pose, objects,
parameters_.object_recognition_collision_check_hard_margins.back())) {
return true;
}
if (utils::checkCollisionBetweenFootprintAndObjects(
vehicle_footprint_, pose, objects,

Check warning on line 448 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp#L448

Added line #L448 was not covered by tests
parameters_.object_recognition_collision_check_hard_margins.back())) {
return true;

Check notice on line 450 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

GoalSearcher::checkCollision 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 450 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp#L450

Added line #L450 was not covered by tests
}
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,8 +105,7 @@

// object recognition
{
const std::string ns = base_ns + "object_recognition.";

Check notice on line 108 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Large Method

GoalPlannerModuleManager::initGoalPlannerParameters decreases from 348 to 347 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
p.use_object_recognition = node->declare_parameter<bool>(ns + "use_object_recognition");
p.object_recognition_collision_check_soft_margins =
node->declare_parameter<std::vector<double>>(ns + "collision_check_soft_margins");
p.object_recognition_collision_check_hard_margins =
Expand Down Expand Up @@ -512,8 +511,7 @@
// object recognition
{
const std::string ns = base_ns + "object_recognition.";

Check notice on line 514 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Large Method

GoalPlannerModuleManager::updateModuleParams decreases from 354 to 353 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
updateParam<bool>(parameters, ns + "use_object_recognition", p->use_object_recognition);
updateParam(
parameters, ns + "object_recognition_collision_check_max_extra_stopping_margin",
p->object_recognition_collision_check_max_extra_stopping_margin);
Expand Down
Loading