Skip to content

Commit 2329708

Browse files
soblinkarishma1911
authored andcommitted
fix(intersection_occlusion): estimate dynamic occlusion source with triangle (autowarefoundation#6585)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent f58d2e5 commit 2329708

File tree

3 files changed

+51
-7
lines changed

3 files changed

+51
-7
lines changed

planning/behavior_velocity_intersection_module/src/debug.cpp

+16
Original file line numberDiff line numberDiff line change
@@ -389,6 +389,22 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
389389
&debug_marker_array, now);
390390
}
391391

392+
if (debug_data_.nearest_occlusion_triangle) {
393+
const auto [p1, p2, p3] = debug_data_.nearest_occlusion_triangle.value();
394+
const auto color = debug_data_.static_occlusion ? green : red;
395+
geometry_msgs::msg::Polygon poly;
396+
poly.points.push_back(
397+
geometry_msgs::build<geometry_msgs::msg::Point32>().x(p1.x).y(p1.y).z(p1.z));
398+
poly.points.push_back(
399+
geometry_msgs::build<geometry_msgs::msg::Point32>().x(p2.x).y(p2.y).z(p2.z));
400+
poly.points.push_back(
401+
geometry_msgs::build<geometry_msgs::msg::Point32>().x(p3.x).y(p3.y).z(p3.z));
402+
appendMarkerArray(
403+
debug::createPolygonMarkerArray(
404+
poly, "nearest_occlusion_triangle", lane_id_, now, 0.3, 0.0, 0.0, std::get<0>(color),
405+
std::get<1>(color), std::get<2>(color)),
406+
&debug_marker_array, now);
407+
}
392408
if (debug_data_.traffic_light_observation) {
393409
const auto GREEN = autoware_perception_msgs::msg::TrafficSignalElement::GREEN;
394410
const auto YELLOW = autoware_perception_msgs::msg::TrafficSignalElement::AMBER;

planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -235,6 +235,10 @@ class IntersectionModule : public SceneModuleInterface
235235
std::vector<geometry_msgs::msg::Polygon> occlusion_polygons;
236236
std::optional<std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
237237
nearest_occlusion_projection{std::nullopt};
238+
std::optional<
239+
std::tuple<geometry_msgs::msg::Point, geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
240+
nearest_occlusion_triangle{std::nullopt};
241+
bool static_occlusion{false};
238242
std::optional<double> static_occlusion_with_traffic_light_timeout{std::nullopt};
239243

240244
std::optional<std::tuple<geometry_msgs::msg::Pose, lanelet::ConstPoint3d, lanelet::Id, uint8_t>>

planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp

+31-7
Original file line numberDiff line numberDiff line change
@@ -334,13 +334,14 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
334334
}
335335
return nearest;
336336
};
337-
struct NearestOcclusionPoint
337+
struct NearestOcclusionInterval
338338
{
339339
int64 division_index{0};
340340
int64 point_index{0};
341341
double dist{0.0};
342342
geometry_msgs::msg::Point point;
343343
geometry_msgs::msg::Point projection;
344+
geometry_msgs::msg::Point visible_end;
344345
} nearest_occlusion_point;
345346
double min_dist = std::numeric_limits<double>::infinity();
346347
for (unsigned division_index = 0; division_index < lane_divisions.size(); ++division_index) {
@@ -370,6 +371,8 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
370371
continue;
371372
}
372373
double acc_dist = 0.0;
374+
bool found_min_dist_for_this_division = false;
375+
bool is_prev_occluded = false;
373376
auto acc_dist_it = projection_it;
374377
for (auto point_it = projection_it; point_it != division.end(); point_it++) {
375378
const double dist =
@@ -386,11 +389,24 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
386389
if (acc_dist < min_dist) {
387390
min_dist = acc_dist;
388391
nearest_occlusion_point = {
389-
division_index, std::distance(division.begin(), point_it), acc_dist,
392+
division_index,
393+
std::distance(division.begin(), point_it),
394+
acc_dist,
390395
tier4_autoware_utils::createPoint(point_it->x(), point_it->y(), origin.z),
391-
tier4_autoware_utils::createPoint(projection_it->x(), projection_it->y(), origin.z)};
396+
tier4_autoware_utils::createPoint(projection_it->x(), projection_it->y(), origin.z),
397+
tier4_autoware_utils::createPoint(
398+
projection_it->x(), projection_it->y(),
399+
origin.z) /* initialize with projection point at first*/};
400+
found_min_dist_for_this_division = true;
401+
} else if (found_min_dist_for_this_division && is_prev_occluded) {
402+
// although this cell is not "nearest" cell, we have found the "nearest" cell on this
403+
// division previously in this iteration, and the iterated cells are still OCCLUDED since
404+
// then
405+
nearest_occlusion_point.visible_end =
406+
tier4_autoware_utils::createPoint(point_it->x(), point_it->y(), origin.z);
392407
}
393408
}
409+
is_prev_occluded = (pixel == OCCLUDED);
394410
}
395411
}
396412

@@ -400,16 +416,24 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
400416

401417
debug_data_.nearest_occlusion_projection =
402418
std::make_pair(nearest_occlusion_point.point, nearest_occlusion_point.projection);
403-
LineString2d ego_occlusion_line;
404-
ego_occlusion_line.emplace_back(current_pose.position.x, current_pose.position.y);
405-
ego_occlusion_line.emplace_back(nearest_occlusion_point.point.x, nearest_occlusion_point.point.y);
419+
debug_data_.nearest_occlusion_triangle = std::make_tuple(
420+
current_pose.position, nearest_occlusion_point.point, nearest_occlusion_point.visible_end);
421+
Polygon2d ego_occlusion_triangle;
422+
ego_occlusion_triangle.outer().emplace_back(current_pose.position.x, current_pose.position.y);
423+
ego_occlusion_triangle.outer().emplace_back(
424+
nearest_occlusion_point.point.x, nearest_occlusion_point.point.y);
425+
ego_occlusion_triangle.outer().emplace_back(
426+
nearest_occlusion_point.visible_end.x, nearest_occlusion_point.visible_end.y);
427+
bg::correct(ego_occlusion_triangle);
406428
for (const auto & attention_object_info : object_info_manager_.allObjects()) {
407429
const auto obj_poly =
408430
tier4_autoware_utils::toPolygon2d(attention_object_info->predicted_object());
409-
if (bg::intersects(obj_poly, ego_occlusion_line)) {
431+
if (bg::intersects(obj_poly, ego_occlusion_triangle)) {
432+
debug_data_.static_occlusion = false;
410433
return DynamicallyOccluded{min_dist};
411434
}
412435
}
436+
debug_data_.static_occlusion = true;
413437
return StaticallyOccluded{min_dist};
414438
}
415439
} // namespace behavior_velocity_planner

0 commit comments

Comments
 (0)