Skip to content

Commit 365323a

Browse files
author
beyza
committed
update collision check for multipolygon
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 50e5fb5 commit 365323a

File tree

1 file changed

+13
-3
lines changed
  • planning/behavior_velocity_dynamic_obstacle_stop_module/src

1 file changed

+13
-3
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp

+13-3
Original file line numberDiff line numberDiff line change
@@ -70,11 +70,21 @@ std::vector<Collision> find_collisions(
7070
const PlannerParam & params)
7171
{
7272
std::vector<Collision> collisions;
73+
std::optional<geometry_msgs::msg::Point> collision;
7374
for (auto object_idx = 0UL; object_idx < objects.size(); ++object_idx) {
7475
const auto & object_pose = objects[object_idx].kinematics.initial_pose_with_covariance.pose;
75-
const auto & object_footprint = object_forward_footprints[object_idx];
76-
const auto collision =
77-
find_closest_collision_point(ego_data, object_pose, object_footprint, params);
76+
if (!params.ignore_objects_behind_ego){
77+
tier4_autoware_utils::MultiPolygon2d object_footprint;
78+
for (const auto &polygon : object_forward_footprints) {
79+
object_footprint.push_back(polygon);
80+
collision =
81+
find_closest_collision_point(ego_data, object_pose, polygon, params);
82+
}
83+
} else {
84+
const auto &object_footprint = object_forward_footprints[object_idx];
85+
collision =
86+
find_closest_collision_point(ego_data, object_pose, object_footprint, params);
87+
}
7888
if (collision) {
7989
Collision c;
8090
c.object_uuid = tier4_autoware_utils::toHexString(objects[object_idx].object_id);

0 commit comments

Comments
 (0)