Skip to content

Commit 5ffc583

Browse files
authored
fix(goal_planner): use precise distance to objects for sorting candidate paths (#10296)
* fix(goal_planner): use precise distance to objects for sorting candidate paths Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * shortest_distance_from_ego_footprint_to_objects_on_path Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * improve doxygen Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> update docs Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * fix build Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> --------- Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent ae5eded commit 5ffc583

File tree

5 files changed

+144
-47
lines changed

5 files changed

+144
-47
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+23-3
Original file line numberDiff line numberDiff line change
@@ -1085,9 +1085,29 @@ void sortPullOverPaths(
10851085
const auto & target_objects = static_target_objects;
10861086
for (const size_t i : sorted_path_indices) {
10871087
const auto & path = pull_over_path_candidates[i];
1088-
const double distance = utils::path_safety_checker::calculateRoughDistanceToObjects(
1089-
path.parking_path(), target_objects, planner_data->parameters, false, "max");
1090-
auto it = std::lower_bound(
1088+
1089+
// check collision roughly with {min_distance, max_distance} between ego footprint and objects
1090+
// footprint
1091+
const std::pair<bool, bool> has_collision_rough =
1092+
utils::path_safety_checker::checkObjectsCollisionRough(
1093+
path.parking_path(), target_objects, soft_margins.front(), hard_margins.back(),
1094+
planner_data->parameters, false);
1095+
// min_distance > soft_margin.front() means no collision with any margin
1096+
if (!has_collision_rough.first) {
1097+
path_id_to_rough_margin_map[path.id()] = soft_margins.front();
1098+
continue;
1099+
}
1100+
// max_distance < hard_margin.front() means collision with any margin
1101+
if (has_collision_rough.second) {
1102+
path_id_to_rough_margin_map[path.id()] = 0.0;
1103+
continue;
1104+
}
1105+
// calculate the precise distance to object footprint from the path footprint
1106+
const double distance =
1107+
utils::path_safety_checker::shortest_distance_from_ego_footprint_to_objects_on_path(
1108+
path.parking_path(), target_objects, planner_data->parameters, true);
1109+
1110+
const auto it = std::lower_bound(
10911111
margins_with_zero.begin(), margins_with_zero.end(), distance, std::greater<double>());
10921112
if (it == margins_with_zero.end()) {
10931113
path_id_to_rough_margin_map[path.id()] = margins_with_zero.back();

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

-12
Original file line numberDiff line numberDiff line change
@@ -324,18 +324,6 @@ bool checkObjectsCollision(
324324
return false;
325325
}
326326

327-
// check collision roughly with {min_distance, max_distance} between ego footprint and objects
328-
// footprint
329-
std::pair<bool, bool> has_collision_rough =
330-
utils::path_safety_checker::checkObjectsCollisionRough(
331-
path, target_objects, collision_check_margin, behavior_path_parameters, false);
332-
if (!has_collision_rough.first) {
333-
return false;
334-
}
335-
if (has_collision_rough.second) {
336-
return true;
337-
}
338-
339327
std::vector<Polygon2d> obj_polygons;
340328
for (const auto & object : target_objects.objects) {
341329
obj_polygons.push_back(autoware_utils::to_polygon2d(object));

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp

+53-18
Original file line numberDiff line numberDiff line change
@@ -252,35 +252,70 @@ double calc_obstacle_min_length(const Shape & shape);
252252
double calc_obstacle_max_length(const Shape & shape);
253253

254254
/**
255-
* @brief Calculate collision roughly by comparing minimum/maximum distance with margin.
256-
* @param path The path of the ego vehicle.
257-
* @param objects The predicted objects.
258-
* @param margin Distance margin to judge collision.
259-
* @param parameters The common parameters used in behavior path planner.
260-
* @param use_offset_ego_point If true, the closest point to the object is calculated by
261-
* interpolating the path points.
262-
* @return Collision (rough) between minimum distance and maximum distance
255+
* @brief Performs efficient rough collision check between ego vehicle and objects
256+
* @details
257+
* This function calculates two types of distances between ego vehicle and each object:
258+
* - Minimum distance: The shortest possible distance between ego and object when positioned
259+
* diagonally with their corners closest to each other (uses maximum extent of both objects)
260+
* - Maximum distance: The largest possible distance between ego and object when positioned parallel
261+
* to each other (uses minimum extent of both objects)
262+
* A collision is detected when:
263+
* - min_distance < min_margin_threshold (first element of returned pair is true)
264+
* - max_distance < max_margin_threshold (second element of returned pair is true)
265+
* This approach provides a computationally efficient rough collision check that can be used
266+
* before performing more expensive precise collision check algorithms.
267+
* @param path The path of the ego vehicle
268+
* @param objects The predicted objects to check for collision
269+
* @param min_margin_threshold Threshold for minimum distance collision check
270+
* @param max_margin_threshold Threshold for maximum distance collision check
271+
* @param parameters The common parameters used in behavior path planner
272+
* @param use_offset_ego_point If true, uses interpolated point on path closest to object
273+
* @return A pair of boolean values {min_distance_collision, max_distance_collision}
263274
*/
264275
std::pair<bool, bool> checkObjectsCollisionRough(
265-
const PathWithLaneId & path, const PredictedObjects & objects, const double margin,
266-
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point);
276+
const PathWithLaneId & path, const PredictedObjects & objects, const double min_margin_threshold,
277+
const double max_margin_threshold, const BehaviorPathPlannerParameters & parameters,
278+
const bool use_offset_ego_point);
279+
280+
/**
281+
* @brief Calculate the shortest rough distance between ego vehicle and objects based on specific
282+
* orientation cases
283+
* @details
284+
* This function calculates a rough estimate of the closest distance between the ego vehicle's path
285+
* and objects by considering two specific orientation cases:
286+
* - "min": Uses the maximum extents of both ego and object (diagonal orientation case)
287+
* This calculates the worst-case, shortest possible distance when objects are oriented to
288+
* minimize the gap between them (when corners face each other)
289+
* - "max": Uses the minimum extents of both ego and object (parallel orientation case)
290+
* This calculates the best-case, longest possible distance when objects are oriented to
291+
* maximize the gap between them (when sides are parallel)
292+
* @param path The path of the ego vehicle
293+
* @param objects The predicted objects to calculate distance to
294+
* @param parameters The common parameters used in behavior path planner
295+
* @param use_offset_ego_point If true, uses interpolated point on path closest to object for more
296+
* accurate calculation
297+
* @param distance_type Either "min" or "max" to specify which orientation case to calculate
298+
* @return The shortest rough distance between the ego vehicle and any object for the specified
299+
* orientation case
300+
*/
301+
double calculateRoughDistanceToObjects(
302+
const PathWithLaneId & path, const PredictedObjects & objects,
303+
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point,
304+
const std::string & distance_type);
267305

268306
/**
269-
* @brief Calculate the rough distance between the ego vehicle and the objects.
307+
* @param Calculate the distance between the path and the closest object
270308
* @param path The path of the ego vehicle.
271309
* @param objects The predicted objects.
272310
* @param parameters The common parameters used in behavior path planner.
273311
* @param use_offset_ego_point If true, the closest point to the object is calculated by
274312
* interpolating the path points.
275-
* @param distance_type The type of distance to calculate. "min" or "max". Calculate the distance
276-
* when the distance is minimized or maximized when the direction of the ego and the object is
277-
* changed.
278-
* @return The rough distance between the ego vehicle and the objects.
313+
* @return The distance between the ego vehicle and the closest object.
279314
*/
280-
double calculateRoughDistanceToObjects(
315+
double shortest_distance_from_ego_footprint_to_objects_on_path(
281316
const PathWithLaneId & path, const PredictedObjects & objects,
282-
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point,
283-
const std::string & distance_type);
317+
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_pose);
318+
284319
// debug
285320
CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj);
286321
void updateCollisionCheckDebugMap(

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

+39-4
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ namespace autoware::behavior_path_planner::utils::path_safety_checker
4141
namespace bg = boost::geometry;
4242

4343
using autoware::motion_utils::calcLongitudinalOffsetPoint;
44+
using autoware::motion_utils::calcLongitudinalOffsetPose;
4445
using autoware::motion_utils::calcLongitudinalOffsetToSegment;
4546
using autoware::motion_utils::findNearestIndex;
4647
using autoware::motion_utils::findNearestSegmentIndex;
@@ -774,8 +775,9 @@ double calc_obstacle_max_length(const Shape & shape)
774775
}
775776

776777
std::pair<bool, bool> checkObjectsCollisionRough(
777-
const PathWithLaneId & path, const PredictedObjects & objects, const double margin,
778-
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point)
778+
const PathWithLaneId & path, const PredictedObjects & objects, const double min_margin_threshold,
779+
const double max_margin_threshold, const BehaviorPathPlannerParameters & parameters,
780+
const bool use_offset_ego_point)
779781
{
780782
const auto & points = path.points;
781783

@@ -815,10 +817,10 @@ std::pair<bool, bool> checkObjectsCollisionRough(
815817
const double min_distance = distance - object_max_length - ego_max_length;
816818
const double max_distance = distance - object_min_length - ego_min_length;
817819

818-
if (min_distance < margin) {
820+
if (min_distance < min_margin_threshold) {
819821
has_collision.first = true;
820822
}
821-
if (max_distance < margin) {
823+
if (max_distance < max_margin_threshold) {
822824
has_collision.second = true;
823825
}
824826
}
@@ -877,6 +879,39 @@ double calculateRoughDistanceToObjects(
877879
return min_distance;
878880
}
879881

882+
double shortest_distance_from_ego_footprint_to_objects_on_path(
883+
const PathWithLaneId & path, const PredictedObjects & objects,
884+
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_pose)
885+
{
886+
const auto & p = parameters;
887+
double min_distance = std::numeric_limits<double>::max();
888+
for (const auto & object : objects.objects) {
889+
const auto & object_point = object.kinematics.initial_pose_with_covariance.pose.position;
890+
891+
const auto ego_pose = std::invoke([&]() -> Pose {
892+
if (use_offset_ego_pose) {
893+
const size_t nearest_segment_idx = findNearestSegmentIndex(path.points, object_point);
894+
const double offset_length =
895+
calcLongitudinalOffsetToSegment(path.points, nearest_segment_idx, object_point);
896+
const auto ego_pose_opt =
897+
calcLongitudinalOffsetPose(path.points, nearest_segment_idx, offset_length);
898+
if (ego_pose_opt.has_value()) return ego_pose_opt.value();
899+
}
900+
const auto ego_nearest_idx = findNearestIndex(path.points, object_point);
901+
return path.points.at(ego_nearest_idx).point.pose;
902+
});
903+
904+
const auto ego_footprint =
905+
autoware_utils::to_footprint(ego_pose, p.base_link2front, p.base_link2rear, p.vehicle_width);
906+
907+
const double distance =
908+
boost::geometry::distance(ego_footprint, autoware_utils::to_polygon2d(object));
909+
min_distance = std::min(min_distance, distance);
910+
}
911+
912+
return min_distance;
913+
}
914+
880915
autoware_internal_planning_msgs::msg::SafetyFactorArray to_safety_factor_array(
881916
const CollisionCheckDebugMap & debug_map)
882917
{

planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp

+29-10
Original file line numberDiff line numberDiff line change
@@ -676,47 +676,66 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, checkObjectsCollisionRough)
676676

677677
auto path = generateTrajectory<PathWithLaneId>(10, 1.0);
678678
autoware_perception_msgs::msg::PredictedObjects objs;
679-
double margin = 0.1;
679+
double min_margin_threshold = 0.1;
680+
double max_margin_threshold = 0.1;
680681
BehaviorPathPlannerParameters param;
681682
param.vehicle_width = 2.0;
682683
param.front_overhang = 1.0;
683684
param.rear_overhang = 1.0;
684685
bool use_offset_ego_point = true;
685686

686-
// Condition: no object
687-
auto rough_object_collision =
688-
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
687+
// Condition: no objects
688+
auto rough_object_collision = checkObjectsCollisionRough(
689+
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
689690
EXPECT_FALSE(rough_object_collision.first);
690691
EXPECT_FALSE(rough_object_collision.second);
691692

692693
// Condition: collides with minimum distance
694+
// min_distance = 0.00464761, max_distance = 2.0
693695
autoware_perception_msgs::msg::PredictedObject obj;
694696
obj.kinematics.initial_pose_with_covariance.pose = createPose(8.0, 3.0, 0.0, 0.0, 0.0, 0.0);
695697
obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX;
696698
obj.shape.dimensions.x = 3.0;
697699
obj.shape.dimensions.y = 1.0;
698700
objs.objects.push_back(obj);
699701

700-
rough_object_collision =
701-
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
702+
rough_object_collision = checkObjectsCollisionRough(
703+
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
702704
EXPECT_TRUE(rough_object_collision.first);
703705
EXPECT_FALSE(rough_object_collision.second);
704706

705707
// Condition: collides with both distance
708+
// min_distance: -1.99535, max_distance: 0.0
706709
obj.kinematics.initial_pose_with_covariance.pose = createPose(2.0, 1.0, 0.0, 0.0, 0.0, 0.0);
707710
objs.objects.clear();
708711
objs.objects.push_back(obj);
709-
rough_object_collision =
710-
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
712+
rough_object_collision = checkObjectsCollisionRough(
713+
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
711714
EXPECT_TRUE(rough_object_collision.first);
712715
EXPECT_TRUE(rough_object_collision.second);
713716

714717
// Condition: use_offset_ego_point set to false
715718
use_offset_ego_point = false;
716-
rough_object_collision =
717-
checkObjectsCollisionRough(path, objs, margin, param, use_offset_ego_point);
719+
rough_object_collision = checkObjectsCollisionRough(
720+
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
718721
EXPECT_TRUE(rough_object_collision.first);
719722
EXPECT_TRUE(rough_object_collision.second);
723+
724+
// Condition: no collision with lenient min_margin_threshold and
725+
// collision with strict max_margin_threshold.
726+
// min_distance = 0.00464761, max_distance = 2.0
727+
min_margin_threshold = 0.001;
728+
max_margin_threshold = 2.1;
729+
obj.kinematics.initial_pose_with_covariance.pose = createPose(8.0, 3.0, 0.0, 0.0, 0.0, 0.0);
730+
obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX;
731+
obj.shape.dimensions.x = 3.0;
732+
obj.shape.dimensions.y = 1.0;
733+
objs.objects.clear();
734+
objs.objects.push_back(obj);
735+
rough_object_collision = checkObjectsCollisionRough(
736+
path, objs, min_margin_threshold, max_margin_threshold, param, use_offset_ego_point);
737+
EXPECT_FALSE(rough_object_collision.first);
738+
EXPECT_TRUE(rough_object_collision.second);
720739
}
721740

722741
TEST(BehaviorPathPlanningSafetyUtilsTest, calculateRoughDistanceToObjects)

0 commit comments

Comments
 (0)