@@ -929,28 +929,29 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
929
929
if (!occlusion_attention_divisions_) {
930
930
occlusion_attention_divisions_ = util::generateDetectionLaneDivisions (
931
931
occlusion_attention_lanelets, routing_graph_ptr,
932
- planner_data_->occupancy_grid ->info .resolution / std::sqrt ( 2.0 ) );
932
+ planner_data_->occupancy_grid ->info .resolution );
933
933
}
934
934
const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value ();
935
935
936
936
const double occlusion_dist_thr = std::fabs (
937
937
std::pow (planner_param_.occlusion .max_vehicle_velocity_for_rss , 2 ) /
938
938
(2 * planner_param_.occlusion .min_vehicle_brake_for_rss ));
939
- std::vector<autoware_auto_perception_msgs::msg::PredictedObject> parked_attention_objects ;
939
+ std::vector<autoware_auto_perception_msgs::msg::PredictedObject> blocking_attention_objects ;
940
940
std::copy_if (
941
941
target_objects.objects .begin (), target_objects.objects .end (),
942
- std::back_inserter (parked_attention_objects ),
942
+ std::back_inserter (blocking_attention_objects ),
943
943
[thresh = planner_param_.occlusion .ignore_parked_vehicle_speed_threshold ](const auto & object) {
944
944
return std::hypot (
945
945
object.kinematics .initial_twist_with_covariance .twist .linear .x ,
946
946
object.kinematics .initial_twist_with_covariance .twist .linear .y ) <= thresh;
947
947
});
948
+ debug_data_.blocking_attention_objects .objects = blocking_attention_objects;
948
949
const bool is_occlusion_cleared =
949
950
(enable_occlusion_detection_ && !occlusion_attention_lanelets.empty () && !is_prioritized)
950
951
? isOcclusionCleared (
951
952
*planner_data_->occupancy_grid , occlusion_attention_area, adjacent_lanelets,
952
953
first_attention_area, interpolated_path_info, occlusion_attention_divisions,
953
- parked_attention_objects , occlusion_dist_thr)
954
+ blocking_attention_objects , occlusion_dist_thr)
954
955
: true ;
955
956
occlusion_stop_state_machine_.setStateWithMarginTime (
956
957
is_occlusion_cleared ? StateMachine::State::GO : StateMachine::STOP,
@@ -1064,9 +1065,11 @@ autoware_auto_perception_msgs::msg::PredictedObjects IntersectionModule::filterT
1064
1065
// check direction of objects
1065
1066
const auto object_direction = util::getObjectPoseWithVelocityDirection (object.kinematics );
1066
1067
const auto is_in_adjacent_lanelets = util::checkAngleForTargetLanelets (
1067
- object_direction, adjacent_lanelets, planner_param_.common .attention_area_angle_thr ,
1068
+ object_direction, object.kinematics .initial_twist_with_covariance .twist .linear .x ,
1069
+ adjacent_lanelets, planner_param_.common .attention_area_angle_thr ,
1068
1070
planner_param_.common .consider_wrong_direction_vehicle ,
1069
- planner_param_.common .attention_area_margin );
1071
+ planner_param_.common .attention_area_margin ,
1072
+ planner_param_.occlusion .ignore_parked_vehicle_speed_threshold );
1070
1073
if (is_in_adjacent_lanelets) {
1071
1074
continue ;
1072
1075
}
@@ -1078,17 +1081,19 @@ autoware_auto_perception_msgs::msg::PredictedObjects IntersectionModule::filterT
1078
1081
if (is_in_intersection_area) {
1079
1082
target_objects.objects .push_back (object);
1080
1083
} else if (util::checkAngleForTargetLanelets (
1081
- object_direction, attention_area_lanelets ,
1082
- planner_param_.common .attention_area_angle_thr ,
1084
+ object_direction, object. kinematics . initial_twist_with_covariance . twist . linear . x ,
1085
+ attention_area_lanelets, planner_param_.common .attention_area_angle_thr ,
1083
1086
planner_param_.common .consider_wrong_direction_vehicle ,
1084
- planner_param_.common .attention_area_margin )) {
1087
+ planner_param_.common .attention_area_margin ,
1088
+ planner_param_.occlusion .ignore_parked_vehicle_speed_threshold )) {
1085
1089
target_objects.objects .push_back (object);
1086
1090
}
1087
1091
} else if (util::checkAngleForTargetLanelets (
1088
- object_direction, attention_area_lanelets ,
1089
- planner_param_.common .attention_area_angle_thr ,
1092
+ object_direction, object. kinematics . initial_twist_with_covariance . twist . linear . x ,
1093
+ attention_area_lanelets, planner_param_.common .attention_area_angle_thr ,
1090
1094
planner_param_.common .consider_wrong_direction_vehicle ,
1091
- planner_param_.common .attention_area_margin )) {
1095
+ planner_param_.common .attention_area_margin ,
1096
+ planner_param_.occlusion .ignore_parked_vehicle_speed_threshold )) {
1092
1097
// intersection_area is not available, use detection_area_with_margin as before
1093
1098
target_objects.objects .push_back (object);
1094
1099
}
@@ -1240,7 +1245,7 @@ bool IntersectionModule::isOcclusionCleared(
1240
1245
const lanelet::CompoundPolygon3d & first_attention_area,
1241
1246
const util::InterpolatedPathInfo & interpolated_path_info,
1242
1247
const std::vector<util::DiscretizedLane> & lane_divisions,
1243
- [[maybe_unused]] const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> &
1248
+ const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> &
1244
1249
blocking_attention_objects,
1245
1250
const double occlusion_dist_thr)
1246
1251
{
@@ -1265,6 +1270,13 @@ bool IntersectionModule::isOcclusionCleared(
1265
1270
const int height = occ_grid.info .height ;
1266
1271
const double resolution = occ_grid.info .resolution ;
1267
1272
const auto & origin = occ_grid.info .origin .position ;
1273
+ auto coord2index = [&](const double x, const double y) {
1274
+ const int idx_x = (x - origin.x ) / resolution;
1275
+ const int idx_y = (y - origin.y ) / resolution;
1276
+ if (idx_x < 0 || idx_x >= width) return std::make_tuple (false , -1 , -1 );
1277
+ if (idx_y < 0 || idx_y >= height) return std::make_tuple (false , -1 , -1 );
1278
+ return std::make_tuple (true , idx_x, idx_y);
1279
+ };
1268
1280
1269
1281
Polygon2d grid_poly;
1270
1282
grid_poly.outer ().emplace_back (origin.x , origin.y );
@@ -1351,8 +1363,39 @@ bool IntersectionModule::isOcclusionCleared(
1351
1363
cv::getStructuringElement (cv::MORPH_RECT, cv::Size (morph_size, morph_size)));
1352
1364
1353
1365
// (3) occlusion mask
1366
+ static constexpr unsigned char OCCLUDED = 255 ;
1367
+ static constexpr unsigned char BLOCKED = 127 ;
1354
1368
cv::Mat occlusion_mask (width, height, CV_8UC1, cv::Scalar (0 ));
1355
1369
cv::bitwise_and (attention_mask, unknown_mask, occlusion_mask);
1370
+ // re-use attention_mask
1371
+ attention_mask = cv::Mat (width, height, CV_8UC1, cv::Scalar (0 ));
1372
+ // (3.1) draw all cells on attention_mask behind blocking vehicles as not occluded
1373
+ std::vector<std::vector<cv::Point >> blocking_polygons;
1374
+ for (const auto & blocking_attention_object : blocking_attention_objects) {
1375
+ const Polygon2d obj_poly = tier4_autoware_utils::toPolygon2d (blocking_attention_object);
1376
+ findCommonCvPolygons (obj_poly.outer (), blocking_polygons);
1377
+ }
1378
+ for (const auto & blocking_polygon : blocking_polygons) {
1379
+ cv::fillPoly (attention_mask, blocking_polygon, cv::Scalar (BLOCKED), cv::LINE_AA);
1380
+ }
1381
+ for (const auto & lane_division : lane_divisions) {
1382
+ const auto & divisions = lane_division.divisions ;
1383
+ for (const auto & division : divisions) {
1384
+ bool blocking_vehicle_found = false ;
1385
+ for (const auto & point_it : division) {
1386
+ const auto [valid, idx_x, idx_y] = coord2index (point_it.x (), point_it.y ());
1387
+ if (!valid) continue ;
1388
+ if (blocking_vehicle_found) {
1389
+ occlusion_mask.at <unsigned char >(height - 1 - idx_y, idx_x) = 0 ;
1390
+ continue ;
1391
+ }
1392
+ if (attention_mask.at <unsigned char >(height - 1 - idx_y, idx_x) == BLOCKED) {
1393
+ blocking_vehicle_found = true ;
1394
+ occlusion_mask.at <unsigned char >(height - 1 - idx_y, idx_x) = 0 ;
1395
+ }
1396
+ }
1397
+ }
1398
+ }
1356
1399
1357
1400
// (4) extract occlusion polygons
1358
1401
const auto & possible_object_bbox = planner_param_.occlusion .possible_object_bbox ;
@@ -1397,19 +1440,11 @@ bool IntersectionModule::isOcclusionCleared(
1397
1440
}
1398
1441
// (4.1) re-draw occluded cells using valid_contours
1399
1442
occlusion_mask = cv::Mat (width, height, CV_8UC1, cv::Scalar (0 ));
1400
- for (unsigned i = 0 ; i < valid_contours. size (); ++i ) {
1443
+ for (const auto & valid_contour : valid_contours) {
1401
1444
// NOTE: drawContour does not work well
1402
- cv::fillPoly (occlusion_mask, valid_contours[i] , cv::Scalar (255 ), cv::LINE_AA);
1445
+ cv::fillPoly (occlusion_mask, valid_contour , cv::Scalar (OCCLUDED ), cv::LINE_AA);
1403
1446
}
1404
1447
1405
- auto coord2index = [&](const double x, const double y) {
1406
- const int idx_x = (x - origin.x ) / resolution;
1407
- const int idx_y = (y - origin.y ) / resolution;
1408
- if (idx_x < 0 || idx_x >= width) return std::make_tuple (false , -1 , -1 );
1409
- if (idx_y < 0 || idx_y >= height) return std::make_tuple (false , -1 , -1 );
1410
- return std::make_tuple (true , idx_x, idx_y);
1411
- };
1412
-
1413
1448
// (5) find distance
1414
1449
// (5.1) discretize path_ip with resolution for computational cost
1415
1450
LineString2d path_linestring;
@@ -1496,7 +1531,11 @@ bool IntersectionModule::isOcclusionCleared(
1496
1531
const auto [valid, idx_x, idx_y] = coord2index (point_it->x (), point_it->y ());
1497
1532
// TODO(Mamoru Sobue): add handling for blocking vehicles
1498
1533
if (!valid) continue ;
1499
- if (occlusion_mask.at <unsigned char >(height - 1 - idx_y, idx_x) == 255 ) {
1534
+ const auto pixel = occlusion_mask.at <unsigned char >(height - 1 - idx_y, idx_x);
1535
+ if (pixel == BLOCKED) {
1536
+ break ;
1537
+ }
1538
+ if (pixel == OCCLUDED) {
1500
1539
if (acc_dist < min_dist) {
1501
1540
min_dist = acc_dist;
1502
1541
nearest_occlusion_point = {
0 commit comments