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

fix(goal_planner): use precise distance to objects for sorting candidate paths #10296

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 @@ -1085,9 +1085,28 @@
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(

// check collision roughly with {min_distance, max_distance} between ego footprint and objects
// footprint
const std::pair<bool, bool> has_collision_rough =
utils::path_safety_checker::checkObjectsCollisionRough(
path.parking_path(), target_objects, soft_margins.front(), hard_margins.back(),

Check warning on line 1093 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#L1093

Added line #L1093 was not covered by tests
planner_data->parameters, false);
// min_distance > soft_margin.front() means no collision with any margin
if (!has_collision_rough.first) {
path_id_to_rough_margin_map[path.id()] = soft_margins.front();
continue;

Check warning on line 1098 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#L1098

Added line #L1098 was not covered by tests
}
// max_distance < hard_margin.front() means collision with any margin
if (has_collision_rough.second) {
path_id_to_rough_margin_map[path.id()] = 0.0;
continue;

Check warning on line 1103 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#L1103

Added line #L1103 was not covered by tests
}
// calculate the precise distance to object footprint from the path footprint
const double distance = utils::path_safety_checker::calculate_distance_to_objects_from_path(
path.parking_path(), target_objects, planner_data->parameters, true);

const 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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -324,18 +324,6 @@ bool checkObjectsCollision(
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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -255,18 +255,20 @@ double calc_obstacle_max_length(const Shape & shape);
* @brief Calculate collision roughly by comparing minimum/maximum distance with margin.
* @param path The path of the ego vehicle.
* @param objects The predicted objects.
* @param margin Distance margin to judge collision.
* @param min_margin_threshold threshold for collision check when the minimum distance between ego
Copy link
Contributor

Choose a reason for hiding this comment

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

英語の文法を分かりやすくして下さい

"threshold for collision check when the minimum distance between ego"

* @param max_margin_threshold threshold for collision check when the maximum distance between ego
* @param parameters The common parameters used in behavior path planner.
* @param use_offset_ego_point If true, the closest point to the object is calculated by
* interpolating the path points.
* @return Collision (rough) between minimum distance and maximum distance
*/
std::pair<bool, bool> checkObjectsCollisionRough(
const PathWithLaneId & path, const PredictedObjects & objects, const double margin,
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point);
const PathWithLaneId & path, const PredictedObjects & objects, const double min_margin_threshold,
const double max_margin_threshold, const BehaviorPathPlannerParameters & parameters,
const bool use_offset_ego_point);

/**
* @brief Calculate the rough distance between the ego vehicle and the objects.
* @brief Calculate the rough distances between the path and the objects and return the minimum
* @param path The path of the ego vehicle.
* @param objects The predicted objects.
* @param parameters The common parameters used in behavior path planner.
Expand All @@ -281,6 +283,20 @@ double calculateRoughDistanceToObjects(
const PathWithLaneId & path, const PredictedObjects & objects,
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point,
const std::string & distance_type);

/**
* @param Calculate the distance between the path and the closest object
* @param path The path of the ego vehicle.
* @param objects The predicted objects.
* @param parameters The common parameters used in behavior path planner.
* @param use_offset_ego_point If true, the closest point to the object is calculated by
* interpolating the path points.
* @return The distance between the ego vehicle and the closest object.
*/
double calculate_distance_to_objects_from_path(
const PathWithLaneId & path, const PredictedObjects & objects,
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_pose);

// debug
CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj);
void updateCollisionCheckDebugMap(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
namespace bg = boost::geometry;

using autoware::motion_utils::calcLongitudinalOffsetPoint;
using autoware::motion_utils::calcLongitudinalOffsetPose;
using autoware::motion_utils::calcLongitudinalOffsetToSegment;
using autoware::motion_utils::findNearestIndex;
using autoware::motion_utils::findNearestSegmentIndex;
Expand Down Expand Up @@ -774,8 +775,9 @@
}

std::pair<bool, bool> checkObjectsCollisionRough(
const PathWithLaneId & path, const PredictedObjects & objects, const double margin,
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point)
const PathWithLaneId & path, const PredictedObjects & objects, const double min_margin_threshold,
const double max_margin_threshold, const BehaviorPathPlannerParameters & parameters,
const bool use_offset_ego_point)
{
const auto & points = path.points;

Expand Down Expand Up @@ -815,10 +817,10 @@
const double min_distance = distance - object_max_length - ego_max_length;
const double max_distance = distance - object_min_length - ego_min_length;

if (min_distance < margin) {
if (min_distance < min_margin_threshold) {
has_collision.first = true;
}
if (max_distance < margin) {
if (max_distance < max_margin_threshold) {
has_collision.second = true;
}
}
Expand Down Expand Up @@ -877,6 +879,40 @@
return min_distance;
}

double calculate_distance_to_objects_from_path(

Check warning on line 882 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L882

Added line #L882 was not covered by tests
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
double calculate_distance_to_objects_from_path(
double shortest_distance_from_ego_footprint_to_objects_on_path(

const PathWithLaneId & path, const PredictedObjects & objects,
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_pose)

{
const auto & p = parameters;
double min_distance = std::numeric_limits<double>::max();

Check warning on line 888 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L888

Added line #L888 was not covered by tests
for (const auto & object : objects.objects) {
const auto & object_point = object.kinematics.initial_pose_with_covariance.pose.position;

Check warning on line 890 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L890

Added line #L890 was not covered by tests

const auto ego_pose = std::invoke([&]() -> Pose {

Check warning on line 892 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L892

Added line #L892 was not covered by tests
if (use_offset_ego_pose) {
const size_t nearest_segment_idx = findNearestSegmentIndex(path.points, object_point);
const double offset_length =
calcLongitudinalOffsetToSegment(path.points, nearest_segment_idx, object_point);

Check warning on line 896 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L896

Added line #L896 was not covered by tests
const auto ego_pose_opt =
calcLongitudinalOffsetPose(path.points, nearest_segment_idx, offset_length);
if (ego_pose_opt.has_value()) return ego_pose_opt.value();
}
const auto ego_nearest_idx = findNearestIndex(path.points, object_point);
return path.points.at(ego_nearest_idx).point.pose;

Check warning on line 902 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L901-L902

Added lines #L901 - L902 were not covered by tests
});

const auto ego_footprint =
autoware_utils::to_footprint(ego_pose, p.base_link2front, p.base_link2rear, p.vehicle_width);

Check warning on line 906 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L906

Added line #L906 was not covered by tests

const double distance =
boost::geometry::distance(ego_footprint, autoware_utils::to_polygon2d(object));
min_distance = std::min(min_distance, distance);
}

Check warning on line 911 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L910-L911

Added lines #L910 - L911 were not covered by tests

return min_distance;

Check warning on line 913 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp#L913

Added line #L913 was not covered by tests
}

autoware_internal_planning_msgs::msg::SafetyFactorArray to_safety_factor_array(
const CollisionCheckDebugMap & debug_map)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -676,47 +676,66 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, checkObjectsCollisionRough)

auto path = generateTrajectory<PathWithLaneId>(10, 1.0);
autoware_perception_msgs::msg::PredictedObjects objs;
double margin = 0.1;
double min_margin_threshold = 0.1;
double max_margin_threshold = 0.1;
BehaviorPathPlannerParameters param;
param.vehicle_width = 2.0;
param.front_overhang = 1.0;
param.rear_overhang = 1.0;
bool use_offset_ego_point = true;

// Condition: no object
auto rough_object_collision =
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
// Condition: no objects
auto rough_object_collision = checkObjectsCollisionRough(
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
EXPECT_FALSE(rough_object_collision.first);
EXPECT_FALSE(rough_object_collision.second);

// Condition: collides with minimum distance
// min_distance = 0.00464761, max_distance = 2.0
autoware_perception_msgs::msg::PredictedObject obj;
obj.kinematics.initial_pose_with_covariance.pose = createPose(8.0, 3.0, 0.0, 0.0, 0.0, 0.0);
obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX;
obj.shape.dimensions.x = 3.0;
obj.shape.dimensions.y = 1.0;
objs.objects.push_back(obj);

rough_object_collision =
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
rough_object_collision = checkObjectsCollisionRough(
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
EXPECT_TRUE(rough_object_collision.first);
EXPECT_FALSE(rough_object_collision.second);

// Condition: collides with both distance
// min_distance: -1.99535, max_distance: 0.0
obj.kinematics.initial_pose_with_covariance.pose = createPose(2.0, 1.0, 0.0, 0.0, 0.0, 0.0);
objs.objects.clear();
objs.objects.push_back(obj);
rough_object_collision =
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
rough_object_collision = checkObjectsCollisionRough(
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
EXPECT_TRUE(rough_object_collision.first);
EXPECT_TRUE(rough_object_collision.second);

// Condition: use_offset_ego_point set to false
use_offset_ego_point = false;
rough_object_collision =
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
rough_object_collision = checkObjectsCollisionRough(
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
EXPECT_TRUE(rough_object_collision.first);
EXPECT_TRUE(rough_object_collision.second);

// Condition: no collision with lenient min_margin_threshold and
// collision with strict max_margin_threshold.
// min_distance = 0.00464761, max_distance = 2.0
min_margin_threshold = 0.001;
max_margin_threshold = 2.1;
obj.kinematics.initial_pose_with_covariance.pose = createPose(8.0, 3.0, 0.0, 0.0, 0.0, 0.0);
obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX;
obj.shape.dimensions.x = 3.0;
obj.shape.dimensions.y = 1.0;
objs.objects.clear();
objs.objects.push_back(obj);
rough_object_collision = checkObjectsCollisionRough(
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
EXPECT_FALSE(rough_object_collision.first);
EXPECT_TRUE(rough_object_collision.second);
}

TEST(BehaviorPathPlanningSafetyUtilsTest, calculateRoughDistanceToObjects)
Expand Down
Loading