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): expand outer collision check margin #10294

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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 @@ -375,6 +375,7 @@ Then there is the concept of soft and hard margins. Although not currently param
| object_recognition_collision_check_soft_margins | [m] | vector[double] | soft margins for collision check when path generation. It is not strictly the distance between footprints, but the maximum distance when ego and objects are oriented. | [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 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 |
| collision_check_outer_margin_factor | [-] | double | factor to extend the collision check margin from the inside margin to the outside in the curved path | 2.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 @@ -42,6 +42,7 @@
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
collision_check_outer_margin_factor: 2.0
th_moving_object_velocity: 1.0
detection_bound_offset: 15.0
outer_road_detection_offset: 1.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.
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ struct GoalPlannerParameters
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 collision_check_outer_margin_factor{0.0};
double th_moving_object_velocity{0.0};
double detection_bound_offset{0.0};
double outer_road_detection_offset{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,14 +128,32 @@ bool isWithinAreas(
*/
std::vector<lanelet::BasicPolygon2d> getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes);

/**
* @brief check collision between objects and ego path footprints
* @param path ego path to check collision
* @param curvatures curvatures of ego path
* @param static_target_objects static objects to check collision
* @param dynamic_target_objects dynamic objects to check collision
* @param behavior_path_parameters behavior path parameters
* @param collision_check_margin margin to check collision
* @param extract_static_objects flag to extract static objects
* @param maximum_deceleration maximum deceleration
* @param object_recognition_collision_check_max_extra_stopping_margin maximum extra stopping margin
* @param collision_check_outer_margin_factor factor to extend the collision check margin from the
* inside margin to the outside in the curved path
* @param ego_polygons_expanded expanded ego polygons
* @param update_debug_data flag to update debug data
* @return true if collision is detected
*/
bool checkObjectsCollision(
const PathWithLaneId & path, const std::vector<double> & curvatures,
const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
const BehaviorPathPlannerParameters & behavior_path_parameters,
const double collision_check_margin, const bool extract_static_objects,
const double maximum_deceleration,
const double object_recognition_collision_check_max_extra_stopping_margin,
std::vector<Polygon2d> & ego_polygons_expanded, const bool update_debug_data = false);
const double collision_check_outer_margin_factor, std::vector<Polygon2d> & ego_polygons_expanded,
const bool update_debug_data = false);

// debug
MarkerArray createPullOverAreaMarkerArray(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ PathDecisionState PathDecisionStateController::get_next_state(
planner_data->parameters, margin,
/*extract_static_objects=*/false, parameters.maximum_deceleration,
parameters.object_recognition_collision_check_max_extra_stopping_margin,
ego_polygons_expanded, true)) {
parameters.collision_check_outer_margin_factor, ego_polygons_expanded, true)) {
RCLCPP_DEBUG(
logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects");
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -966,7 +966,7 @@
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)) {
parameters_.collision_check_outer_margin_factor, debug_data_.ego_polygons_expanded)) {

Check warning on line 969 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#L969

Added line #L969 was not covered by tests
return false;
}

Expand Down Expand Up @@ -1258,7 +1258,8 @@
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)) {
parameters_.collision_check_outer_margin_factor, debug_data_.ego_polygons_expanded,
true)) {

Check warning on line 1262 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 worse: Complex Method

GoalPlannerModule::selectPullOverPath already has high cyclomatic complexity, and now it increases in Lines of Code from 74 to 75. 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 @@ -1933,7 +1934,7 @@
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)) {
parameters.collision_check_outer_margin_factor, ego_polygons_expanded)) {
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,8 @@
p.object_recognition_collision_check_max_extra_stopping_margin =
node->declare_parameter<double>(
ns + "object_recognition_collision_check_max_extra_stopping_margin");
p.collision_check_outer_margin_factor =
node->declare_parameter<double>(ns + "collision_check_outer_margin_factor");

Check warning on line 117 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 worse: Complex Method

GoalPlannerModuleManager::initGoalPlannerParameters already has high cyclomatic complexity, and now it increases in Lines of Code from 350 to 352. 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.
p.th_moving_object_velocity = node->declare_parameter<double>(ns + "th_moving_object_velocity");
p.detection_bound_offset = node->declare_parameter<double>(ns + "detection_bound_offset");
p.outer_road_detection_offset =
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_planner/autoware_behavior_path_goal_planner_module/src/util.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 4.41 to 4.38, 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 @@ -309,63 +309,53 @@
const double collision_check_margin, const bool extract_static_objects,
const double maximum_deceleration,
const double object_recognition_collision_check_max_extra_stopping_margin,
const double collision_check_outer_margin_factor,
std::vector<Polygon2d> & debug_ego_polygons_expanded, const bool update_debug_data)
{
if (path.points.size() != curvatures.size()) {
RCLCPP_WARN(
rclcpp::get_logger("goal_planner_util"),
"path.points.size() != curvatures.size() in checkObjectsCollision(). judge as non collision");
return false;
}

const auto & target_objects =
extract_static_objects ? static_target_objects : dynamic_target_objects;
if (target_objects.objects.empty()) {
return false;
}

// check collision roughly with {min_distance, max_distance} between ego footprint and objects
// footprint
std::pair<bool, bool> has_collision_rough =
utils::path_safety_checker::checkObjectsCollisionRough(
path, target_objects, collision_check_margin, behavior_path_parameters, false);
if (!has_collision_rough.first) {
return false;
}
if (has_collision_rough.second) {
return true;
}

std::vector<Polygon2d> obj_polygons;
for (const auto & object : target_objects.objects) {
obj_polygons.push_back(autoware_utils::to_polygon2d(object));
}

/* Expand ego collision check polygon
* - `collision_check_margin` is added in all directions.
* - `extra_stopping_margin` adds stopping margin under deceleration constraints forward.
* - `extra_lateral_margin` adds the lateral margin on curves.
*/
std::vector<Polygon2d> ego_polygons_expanded{};
for (size_t i = 0; i < path.points.size(); ++i) {
const auto p = path.points.at(i);
const double extra_stopping_margin = std::min(
std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / maximum_deceleration,
object_recognition_collision_check_max_extra_stopping_margin);

// The square is meant to imply centrifugal force, but it is not a very well-founded formula.
// TODO(kosuke55): It is needed to consider better way because there is an inherently
// different conception of the inside and outside margins.
const double curvature = curvatures.at(i);
const double extra_lateral_margin = std::min(
extra_stopping_margin,
std::abs(curvatures.at(i) * std::pow(p.point.longitudinal_velocity_mps, 2)));

extra_stopping_margin, std::abs(curvature * std::pow(p.point.longitudinal_velocity_mps, 2)));
// The outer margin is `collision_check_outer_margin_factor` times larger than the inner margin.
const double sign = curvature > 0.0 ? -1.0 : 1.0;
const auto ego_pose_offset = calc_offset_pose(

Check warning on line 350 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L350

Added line #L350 was not covered by tests
p.point.pose, 0.0, sign * (collision_check_outer_margin_factor - 1.0) * extra_lateral_margin,
0.0);
const auto ego_polygon = autoware_utils::to_footprint(
p.point.pose,
ego_pose_offset,
behavior_path_parameters.base_link2front + collision_check_margin + extra_stopping_margin,
behavior_path_parameters.base_link2rear + collision_check_margin,
behavior_path_parameters.vehicle_width + collision_check_margin * 2.0 +
extra_lateral_margin * 2.0);
extra_lateral_margin * (collision_check_outer_margin_factor + 1.0));

Check notice on line 358 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

checkObjectsCollision 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.
ego_polygons_expanded.push_back(ego_polygon);
}

Expand Down
Loading