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): change pull over path candidate priority with soft and hard margins #6412

Merged
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
13 changes: 7 additions & 6 deletions planning/behavior_path_goal_planner_module/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -339,12 +339,13 @@ Then there is the concept of soft and hard margins. Although not currently param

#### Parameters for object recognition based collision check

| Name | Unit | Type | Description | Default value |
| :----------------------------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------- | :------------ |
| use_object_recognition | [-] | bool | flag whether to use object recognition for collision check | true |
| object_recognition_collision_check_margin | [m] | double | margin to calculate ego-vehicle cells from footprint. | 0.6 |
| object_recognition_collision_check_max_extra_stopping_margin | [m] | double | maximum value when adding longitudinal distance margin for collision check considering stopping distance | 1.0 |
| detection_bound_offset | [m] | double | expand pull over lane with this offset to make detection area for collision check of path generation | 15.0 |
| Name | Unit | Type | Description | Default value |
| :----------------------------------------------------------- | :--- | :------------- | :------------------------------------------------------------------------------------------------------- | :-------------- |
| use_object_recognition | [-] | bool | flag whether to use object recognition for collision check | true |
| object_recognition_collision_check_soft_margins | [m] | vector[double] | soft margins for collision check when path generation | [2.0, 1.5, 1.0] |
| object_recognition_collision_check_hard_margins | [m] | vector[double] | hard margins for collision check when path generation | [0.6] |
| object_recognition_collision_check_max_extra_stopping_margin | [m] | double | maximum value when adding longitudinal distance margin for collision check considering stopping distance | 1.0 |
| detection_bound_offset | [m] | double | expand pull over lane with this offset to make detection area for collision check of path generation | 15.0 |

## **safety check**

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@
# object recognition
object_recognition:
use_object_recognition: false
object_recognition_collision_check_margin: 0.6 # this should be larger than `surround_check_distance` of surround_obstacle_checker
collision_check_soft_margins: [2.0, 1.5, 1.0]
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
th_moving_object_velocity: 1.0
detection_bound_offset: 15.0
Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,8 @@ struct GoalPlannerParameters

// object recognition
bool use_object_recognition{false};
double object_recognition_collision_check_margin{0.0};
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};
double th_moving_object_velocity{0.0};
double detection_bound_offset{0.0};
Expand Down
118 changes: 96 additions & 22 deletions planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp
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 1660 to 1717, 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 4.91 to 5.06, 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 @@ -642,7 +642,7 @@
if (
parameters_->use_object_recognition &&
checkObjectsCollision(
path, parameters_->object_recognition_collision_check_margin,
path, parameters_->object_recognition_collision_check_hard_margins.back(),
/*extract_static_objects=*/false)) {
return false;
}
Expand Down Expand Up @@ -697,7 +697,37 @@
const std::vector<PullOverPath> & pull_over_path_candidates,
const GoalCandidates & goal_candidates) const
{
auto sorted_pull_over_path_candidates = pull_over_path_candidates;
// ==========================================================================================
// print path priority for debug
const auto debugPrintPathPriority =
[this](

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L703

Added line #L703 was not covered by tests
const std::vector<PullOverPath> & sorted_pull_over_path_candidates,
const std::map<size_t, size_t> & goal_id_to_index,
const std::optional<std::map<size_t, double>> & path_id_to_margin_map_opt = std::nullopt,
const std::optional<std::function<bool(const PullOverPath &)>> & isSoftMarginOpt =
std::nullopt) {
std::stringstream ss;
ss << "\n---------------------- path priority ----------------------\n";
for (const auto & path : sorted_pull_over_path_candidates) {

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L708-L711

Added lines #L708 - L711 were not covered by tests
// clang-format off
ss << "path_type: " << magic_enum::enum_name(path.type)
<< ", path_id: " << path.id
<< ", goal_id: " << path.goal_id
<< ", goal_priority:" << goal_id_to_index.at(path.goal_id);

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L713-L716

Added lines #L713 - L716 were not covered by tests
// clang-format on
if (path_id_to_margin_map_opt && isSoftMarginOpt) {
ss << ", margin: " << path_id_to_margin_map_opt->at(path.id)
<< ((*isSoftMarginOpt)(path) ? " (soft)" : " (hard)");

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L718-L720

Added lines #L718 - L720 were not covered by tests
}
ss << "\n";

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L722

Added line #L722 was not covered by tests
}
ss << "-----------------------------------------------------------\n";
RCLCPP_DEBUG_STREAM(getLogger(), ss.str());
};

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L724-L726

Added lines #L724 - L726 were not covered by tests
// ==========================================================================================

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 730 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L729-L730

Added lines #L729 - L730 were not covered by tests

// Create a map of goal_id to its index in goal_candidates
std::map<size_t, size_t> goal_id_to_index;
Expand All @@ -706,13 +736,29 @@
}

// Sort pull_over_path_candidates based on the order in goal_candidates
auto sorted_pull_over_path_candidates = pull_over_path_candidates;

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L739

Added line #L739 was not covered by tests
std::stable_sort(
sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(),
[&goal_id_to_index](const auto & a, const auto & b) {
return goal_id_to_index[a.goal_id] < goal_id_to_index[b.goal_id];
});

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

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L747-L752

Added lines #L747 - L752 were not covered by tests

// if object recognition is enabled, sort by collision check margin
if (parameters_->use_object_recognition) {
const std::vector<double> margins = std::invoke([&]() {
std::vector<double> combined_margins = soft_margins;
combined_margins.insert(combined_margins.end(), hard_margins.begin(), hard_margins.end());
return combined_margins;
});

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L756-L760

Added lines #L756 - L760 were not covered by tests

Comment on lines +756 to +761
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
const std::vector<double> margins = std::invoke([&]() {
std::vector<double> combined_margins = soft_margins;
combined_margins.insert(combined_margins.end(), hard_margins.begin(), hard_margins.end());
return combined_margins;
});
std::vector<double> margins = soft_margins;
margins.insert(margins.end(), hard_margins.begin(), hard_margins.end());

[super nits] simpler?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I like const...

// Create a map of PullOverPath pointer to largest collision check margin
auto calcLargestMargin = [&](const PullOverPath & pull_over_path) {
// check has safe goal
Expand All @@ -724,16 +770,14 @@
if (goal_candidate_it != goal_candidates.end() && !goal_candidate_it->is_safe) {
return 0.0;
}
// calc largest margin
std::vector<double> scale_factors{3.0, 2.0, 1.0};
const double margin = parameters_->object_recognition_collision_check_margin;
// check path collision margin
const auto resampled_path =
utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5);
for (const auto & scale_factor : scale_factors) {
for (const auto & margin : margins) {

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L776

Added line #L776 was not covered by tests
if (!checkObjectsCollision(
resampled_path, margin * scale_factor,
resampled_path, margin,
/*extract_static_objects=*/true)) {
return margin * scale_factor;
return margin;

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L780

Added line #L780 was not covered by tests
}
}
return 0.0;
Expand All @@ -754,18 +798,44 @@
}
return path_id_to_margin_map[a.id] > path_id_to_margin_map[b.id];
});
}

// Sort pull_over_path_candidates based on the order in efficient_path_order
if (parameters_->path_priority == "efficient_path") {
std::stable_sort(
sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(),
[this](const auto & a, const auto & b) {
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;
});
// Sort pull_over_path_candidates based on the order in efficient_path_order
if (parameters_->path_priority == "efficient_path") {
const auto isSoftMargin = [&](const PullOverPath & path) -> bool {
const double margin = path_id_to_margin_map[path.id];

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L803-L805

Added lines #L803 - L805 were not covered by tests
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_margin_map[a.id] - path_id_to_margin_map[b.id]) < 0.01;
};

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L807-L813

Added lines #L807 - L813 were not covered by tests

std::stable_sort(

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L815

Added line #L815 was not covered by tests
sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(),
[&](const auto & a, const auto & b) {

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L817

Added line #L817 was not covered by tests
// if both are soft margin or both are same hard margin, sort by planner priority
if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) {

Check warning on line 819 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)

❌ New issue: Complex Conditional

GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority has 1 complex conditionals with 2 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.
return comparePathTypePriority(a, b);

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L819-L820

Added lines #L819 - L820 were not covered by tests
}
// otherwise, keep the order.
return false;
});

// debug print path priority: sorted by efficient_path_order and collision check margin
debugPrintPathPriority(

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L827

Added line #L827 was not covered by tests
sorted_pull_over_path_candidates, goal_id_to_index, path_id_to_margin_map, isSoftMargin);
}
} else {
// Sort pull_over_path_candidates based on the order in efficient_path_order
if (parameters_->path_priority == "efficient_path") {
std::stable_sort(

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L832-L833

Added lines #L832 - L833 were not covered by tests
sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(),
[&](const auto & a, const auto & b) { return comparePathTypePriority(a, b); });

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L835

Added line #L835 was not covered by tests
// debug print path priority: sorted by efficient_path_order and collision check margin
debugPrintPathPriority(sorted_pull_over_path_candidates, goal_id_to_index);

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L837

Added line #L837 was not covered by tests
}

Check warning on line 838 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::sortPullOverPathCandidatesByGoalPriority increases in cyclomatic complexity from 10 to 20, 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 warning on line 838 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: Bumpy Road Ahead

GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority increases from 2 to 5 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.
}

return sorted_pull_over_path_candidates;
Expand Down Expand Up @@ -979,7 +1049,7 @@
// check current parking path collision
const auto parking_path = utils::resamplePathWithSpline(pull_over_path->getParkingPath(), 0.5);
const double margin =
parameters_->object_recognition_collision_check_margin * hysteresis_factor;
parameters_->object_recognition_collision_check_hard_margins.back() * hysteresis_factor;

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1052

Added line #L1052 was not covered by tests
if (checkObjectsCollision(parking_path, margin, /*extract_static_objects=*/false)) {
RCLCPP_DEBUG(
getLogger(),
Expand Down Expand Up @@ -1115,14 +1185,17 @@
// select pull over path which is safe against static objects and get it's goal
const auto path_and_goal_opt = selectPullOverPath(
pull_over_path_candidates, goal_candidates,
parameters_->object_recognition_collision_check_margin);
parameters_->object_recognition_collision_check_hard_margins.back());

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1188

Added line #L1188 was not covered by tests

// update thread_safe_data_
if (path_and_goal_opt) {
auto [pull_over_path, modified_goal] = *path_and_goal_opt;
deceleratePath(pull_over_path);
thread_safe_data_.set(
goal_candidates, pull_over_path_candidates, pull_over_path, modified_goal);
RCLCPP_DEBUG(

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1196

Added line #L1196 was not covered by tests
getLogger(), "selected pull over path: path_id: %ld, goal_id: %ld", pull_over_path.id,
modified_goal.id);
} else {
thread_safe_data_.set(goal_candidates, pull_over_path_candidates);
}
Expand Down Expand Up @@ -1436,7 +1509,8 @@
parameters_->use_object_recognition &&
checkObjectsCollision(
thread_safe_data_.get_pull_over_path()->getCurrentPath(),
/*extract_static_objects=*/false, parameters_->object_recognition_collision_check_margin)) {
/*extract_static_objects=*/false,
parameters_->object_recognition_collision_check_hard_margins.back())) {

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1513

Added line #L1513 was not covered by tests
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,7 @@
transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(p.point.pose));
const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object);
const double distance = boost::geometry::distance(obj_polygon, transformed_vehicle_footprint);
if (distance > parameters_.object_recognition_collision_check_margin) {
if (distance > parameters_.object_recognition_collision_check_hard_margins.back()) {

Check warning on line 250 in planning/behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_searcher.cpp#L250

Added line #L250 was not covered by tests
continue;
}
const Pose & object_pose = object.kinematics.initial_pose_with_covariance.pose;
Expand Down Expand Up @@ -302,7 +302,7 @@
constexpr bool filter_inside = true;
const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance(
goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects,
parameters_.object_recognition_collision_check_margin, filter_inside);
parameters_.object_recognition_collision_check_hard_margins.back(), filter_inside);

Check warning on line 305 in planning/behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_searcher.cpp#L305

Added line #L305 was not covered by tests
if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) {
goal_candidate.is_safe = false;
continue;
Expand Down Expand Up @@ -330,7 +330,8 @@
parameters_.forward_goal_search_length, parameters_.detection_bound_offset,
*(planner_data_->dynamic_object), parameters_.th_moving_object_velocity);

const double margin = parameters_.object_recognition_collision_check_margin * margin_scale_factor;
const double margin =
parameters_.object_recognition_collision_check_hard_margins.back() * margin_scale_factor;

Check warning on line 334 in planning/behavior_path_goal_planner_module/src/goal_searcher.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_searcher.cpp#L334

Added line #L334 was not covered by tests

if (utils::checkCollisionBetweenFootprintAndObjects(
vehicle_footprint_, goal_pose, pull_over_lane_stop_objects, margin)) {
Expand Down Expand Up @@ -364,7 +365,7 @@
if (parameters_.use_object_recognition) {
if (utils::checkCollisionBetweenFootprintAndObjects(
vehicle_footprint_, pose, objects,
parameters_.object_recognition_collision_check_margin)) {
parameters_.object_recognition_collision_check_hard_margins.back())) {
return true;
}
}
Expand Down
18 changes: 16 additions & 2 deletions planning/behavior_path_goal_planner_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,8 +95,10 @@
{
const std::string ns = base_ns + "object_recognition.";
p.use_object_recognition = node->declare_parameter<bool>(ns + "use_object_recognition");
p.object_recognition_collision_check_margin =
node->declare_parameter<double>(ns + "object_recognition_collision_check_margin");
p.object_recognition_collision_check_soft_margins =
node->declare_parameter<std::vector<double>>(ns + "collision_check_soft_margins");

Check warning on line 99 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/manager.cpp#L99

Added line #L99 was not covered by tests
p.object_recognition_collision_check_hard_margins =
node->declare_parameter<std::vector<double>>(ns + "collision_check_hard_margins");

Check warning on line 101 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/manager.cpp#L101

Added line #L101 was not covered by tests
p.object_recognition_collision_check_max_extra_stopping_margin =
node->declare_parameter<double>(
ns + "object_recognition_collision_check_max_extra_stopping_margin");
Expand All @@ -106,6 +108,18 @@
node->declare_parameter<double>(ns + "outer_road_detection_offset");
p.inner_road_detection_offset =
node->declare_parameter<double>(ns + "inner_road_detection_offset");

// validate object recognition collision check margins
if (
p.object_recognition_collision_check_soft_margins.empty() ||

Check warning on line 114 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/manager.cpp#L114

Added line #L114 was not covered by tests
p.object_recognition_collision_check_hard_margins.empty()) {
RCLCPP_FATAL_STREAM(

Check warning on line 116 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/manager.cpp#L116

Added line #L116 was not covered by tests
node->get_logger().get_child(name()),
"object_recognition.collision_check_soft_margins and "
<< "object_recognition.collision_check_hard_margins must not be empty. "
<< "Terminating the program...");
exit(EXIT_FAILURE);

Check warning on line 121 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/manager.cpp#L121

Added line #L121 was not covered by tests
}

Check warning on line 122 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

GoalPlannerModuleManager::init increases from 327 to 339 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.
}

// pull over general params
Expand Down
Loading