@@ -47,10 +47,23 @@ IntersectionModule::getOcclusionStatus(
47
47
(planner_param_.occlusion .enable && !occlusion_attention_lanelets.empty () && !is_amber_or_red)
48
48
? detectOcclusion (interpolated_path_info)
49
49
: NotOccluded{};
50
- occlusion_stop_state_machine_.setStateWithMarginTime (
51
- std::holds_alternative<NotOccluded>(occlusion_status) ? StateMachine::State::GO
52
- : StateMachine::STOP,
53
- logger_.get_child (" occlusion_stop" ), *clock_);
50
+
51
+ // ==========================================================================================
52
+ // if the traffic light changed from green to yellow/red, hysteresis time for occlusion is
53
+ // unnecessary
54
+ // ==========================================================================================
55
+ const auto transition_to_prioritized =
56
+ (previous_prioritized_level_ == TrafficPrioritizedLevel::NOT_PRIORITIZED &&
57
+ traffic_prioritized_level != TrafficPrioritizedLevel::NOT_PRIORITIZED);
58
+ if (transition_to_prioritized) {
59
+ occlusion_stop_state_machine_.setState (StateMachine::State::GO);
60
+ } else {
61
+ occlusion_stop_state_machine_.setStateWithMarginTime (
62
+ std::holds_alternative<NotOccluded>(occlusion_status) ? StateMachine::State::GO
63
+ : StateMachine::STOP,
64
+ logger_.get_child (" occlusion_stop" ), *clock_);
65
+ }
66
+
54
67
const bool is_occlusion_cleared_with_margin =
55
68
(occlusion_stop_state_machine_.getState () == StateMachine::State::GO); // module's detection
56
69
// distinguish if ego detected occlusion or RTC detects occlusion
@@ -318,13 +331,14 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
318
331
}
319
332
return nearest;
320
333
};
321
- struct NearestOcclusionPoint
334
+ struct NearestOcclusionInterval
322
335
{
323
336
int64 division_index{0 };
324
337
int64 point_index{0 };
325
338
double dist{0.0 };
326
339
geometry_msgs::msg::Point point;
327
340
geometry_msgs::msg::Point projection;
341
+ geometry_msgs::msg::Point visible_end;
328
342
} nearest_occlusion_point;
329
343
double min_dist = std::numeric_limits<double >::infinity ();
330
344
for (unsigned division_index = 0 ; division_index < lane_divisions.size (); ++division_index) {
@@ -354,6 +368,8 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
354
368
continue ;
355
369
}
356
370
double acc_dist = 0.0 ;
371
+ bool found_min_dist_for_this_division = false ;
372
+ bool is_prev_occluded = false ;
357
373
auto acc_dist_it = projection_it;
358
374
for (auto point_it = projection_it; point_it != division.end (); point_it++) {
359
375
const double dist =
@@ -370,11 +386,24 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
370
386
if (acc_dist < min_dist) {
371
387
min_dist = acc_dist;
372
388
nearest_occlusion_point = {
373
- division_index, std::distance (division.begin (), point_it), acc_dist,
389
+ division_index,
390
+ std::distance (division.begin (), point_it),
391
+ acc_dist,
374
392
tier4_autoware_utils::createPoint (point_it->x (), point_it->y (), origin.z ),
375
- tier4_autoware_utils::createPoint (projection_it->x (), projection_it->y (), origin.z )};
393
+ tier4_autoware_utils::createPoint (projection_it->x (), projection_it->y (), origin.z ),
394
+ tier4_autoware_utils::createPoint (
395
+ projection_it->x (), projection_it->y (),
396
+ origin.z ) /* initialize with projection point at first*/ };
397
+ found_min_dist_for_this_division = true ;
398
+ } else if (found_min_dist_for_this_division && is_prev_occluded) {
399
+ // although this cell is not "nearest" cell, we have found the "nearest" cell on this
400
+ // division previously in this iteration, and the iterated cells are still OCCLUDED since
401
+ // then
402
+ nearest_occlusion_point.visible_end =
403
+ tier4_autoware_utils::createPoint (point_it->x (), point_it->y (), origin.z );
376
404
}
377
405
}
406
+ is_prev_occluded = (pixel == OCCLUDED);
378
407
}
379
408
}
380
409
@@ -384,16 +413,24 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
384
413
385
414
debug_data_.nearest_occlusion_projection =
386
415
std::make_pair (nearest_occlusion_point.point , nearest_occlusion_point.projection );
387
- LineString2d ego_occlusion_line;
388
- ego_occlusion_line.emplace_back (current_pose.position .x , current_pose.position .y );
389
- ego_occlusion_line.emplace_back (nearest_occlusion_point.point .x , nearest_occlusion_point.point .y );
416
+ debug_data_.nearest_occlusion_triangle = std::make_tuple (
417
+ current_pose.position , nearest_occlusion_point.point , nearest_occlusion_point.visible_end );
418
+ Polygon2d ego_occlusion_triangle;
419
+ ego_occlusion_triangle.outer ().emplace_back (current_pose.position .x , current_pose.position .y );
420
+ ego_occlusion_triangle.outer ().emplace_back (
421
+ nearest_occlusion_point.point .x , nearest_occlusion_point.point .y );
422
+ ego_occlusion_triangle.outer ().emplace_back (
423
+ nearest_occlusion_point.visible_end .x , nearest_occlusion_point.visible_end .y );
424
+ bg::correct (ego_occlusion_triangle);
390
425
for (const auto & attention_object_info : object_info_manager_.allObjects ()) {
391
426
const auto obj_poly =
392
427
tier4_autoware_utils::toPolygon2d (attention_object_info->predicted_object ());
393
- if (bg::intersects (obj_poly, ego_occlusion_line)) {
428
+ if (bg::intersects (obj_poly, ego_occlusion_triangle)) {
429
+ debug_data_.static_occlusion = false ;
394
430
return DynamicallyOccluded{min_dist};
395
431
}
396
432
}
433
+ debug_data_.static_occlusion = true ;
397
434
return StaticallyOccluded{min_dist};
398
435
}
399
436
} // namespace behavior_velocity_planner
0 commit comments