Skip to content

Commit 93b6118

Browse files
authored
feat(intersection): ignore occlusion behind blocking vehicle (#5122)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 14ef695 commit 93b6118

File tree

7 files changed

+2714
-32
lines changed

7 files changed

+2714
-32
lines changed

planning/behavior_velocity_intersection_module/README.md

+10
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,16 @@ If a stopline is associated with the intersection lane, that line is used as the
9494

9595
To avoid a rapid braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) are needed to stop just in front of the attention area, this module does not insert stopline after passing the default stopline position.
9696

97+
### Occlusion detection
98+
99+
If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough the ego vehicle will once stop at the _default stop line_ for `occlusion.before_creep_stop_time`, and then slowly creep toward _occlusion peeking stop line_ at the speed of `occlusion.occlusion_creep_velocity` if `occlusion.enable_creeping` is true. During the creeping if collision is detected this module inserts a stop line instantly, and if the FOV gets sufficiently clear the _intersection occlusion_ wall will disappear. If occlusion is cleared and no collision is detected the ego vehicle will pass the intersection.
100+
101+
The occlusion is detected as the common area of occlusion attention area(which is partially the same as the normal attention area) and the unknown cells of the occupancy grid map. The occupancy grid map is denoised using morphology with the window size of `occlusion.denoise_kernel`. The occlusion attention area lanes are discretized to line strings and they are used to generate a grid whose each cell represents the distance from the ego path along the lane as shown below.
102+
103+
![occlusion_detection](./docs/occlusion_grid.drawio.svg)
104+
105+
If the nearest occlusion cell value is below the threshold, occlusion is detected. It is expected that the occlusion gets cleared as the vehicle approaches the occlusion peeking stop line.
106+
97107
### Module Parameters
98108

99109
| Parameter | Type | Description |

planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg

+2,616
Loading

planning/behavior_velocity_intersection_module/src/debug.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -230,6 +230,12 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
230230
debug_data_.stuck_targets, "stuck_targets", module_id_, now, 0.99, 0.99, 0.2),
231231
&debug_marker_array, now);
232232

233+
appendMarkerArray(
234+
debug::createObjectsMarkerArray(
235+
debug_data_.blocking_attention_objects, "blocking_attention_objects", module_id_, now, 0.99,
236+
0.99, 0.6),
237+
&debug_marker_array, now);
238+
233239
/*
234240
appendMarkerArray(
235241
createPoseMarkerArray(

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+63-24
Original file line numberDiff line numberDiff line change
@@ -929,28 +929,29 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
929929
if (!occlusion_attention_divisions_) {
930930
occlusion_attention_divisions_ = util::generateDetectionLaneDivisions(
931931
occlusion_attention_lanelets, routing_graph_ptr,
932-
planner_data_->occupancy_grid->info.resolution / std::sqrt(2.0));
932+
planner_data_->occupancy_grid->info.resolution);
933933
}
934934
const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value();
935935

936936
const double occlusion_dist_thr = std::fabs(
937937
std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) /
938938
(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;
940940
std::copy_if(
941941
target_objects.objects.begin(), target_objects.objects.end(),
942-
std::back_inserter(parked_attention_objects),
942+
std::back_inserter(blocking_attention_objects),
943943
[thresh = planner_param_.occlusion.ignore_parked_vehicle_speed_threshold](const auto & object) {
944944
return std::hypot(
945945
object.kinematics.initial_twist_with_covariance.twist.linear.x,
946946
object.kinematics.initial_twist_with_covariance.twist.linear.y) <= thresh;
947947
});
948+
debug_data_.blocking_attention_objects.objects = blocking_attention_objects;
948949
const bool is_occlusion_cleared =
949950
(enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_prioritized)
950951
? isOcclusionCleared(
951952
*planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets,
952953
first_attention_area, interpolated_path_info, occlusion_attention_divisions,
953-
parked_attention_objects, occlusion_dist_thr)
954+
blocking_attention_objects, occlusion_dist_thr)
954955
: true;
955956
occlusion_stop_state_machine_.setStateWithMarginTime(
956957
is_occlusion_cleared ? StateMachine::State::GO : StateMachine::STOP,
@@ -1064,9 +1065,11 @@ autoware_auto_perception_msgs::msg::PredictedObjects IntersectionModule::filterT
10641065
// check direction of objects
10651066
const auto object_direction = util::getObjectPoseWithVelocityDirection(object.kinematics);
10661067
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,
10681070
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);
10701073
if (is_in_adjacent_lanelets) {
10711074
continue;
10721075
}
@@ -1078,17 +1081,19 @@ autoware_auto_perception_msgs::msg::PredictedObjects IntersectionModule::filterT
10781081
if (is_in_intersection_area) {
10791082
target_objects.objects.push_back(object);
10801083
} 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,
10831086
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)) {
10851089
target_objects.objects.push_back(object);
10861090
}
10871091
} 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,
10901094
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)) {
10921097
// intersection_area is not available, use detection_area_with_margin as before
10931098
target_objects.objects.push_back(object);
10941099
}
@@ -1240,7 +1245,7 @@ bool IntersectionModule::isOcclusionCleared(
12401245
const lanelet::CompoundPolygon3d & first_attention_area,
12411246
const util::InterpolatedPathInfo & interpolated_path_info,
12421247
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> &
12441249
blocking_attention_objects,
12451250
const double occlusion_dist_thr)
12461251
{
@@ -1265,6 +1270,13 @@ bool IntersectionModule::isOcclusionCleared(
12651270
const int height = occ_grid.info.height;
12661271
const double resolution = occ_grid.info.resolution;
12671272
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+
};
12681280

12691281
Polygon2d grid_poly;
12701282
grid_poly.outer().emplace_back(origin.x, origin.y);
@@ -1351,8 +1363,39 @@ bool IntersectionModule::isOcclusionCleared(
13511363
cv::getStructuringElement(cv::MORPH_RECT, cv::Size(morph_size, morph_size)));
13521364

13531365
// (3) occlusion mask
1366+
static constexpr unsigned char OCCLUDED = 255;
1367+
static constexpr unsigned char BLOCKED = 127;
13541368
cv::Mat occlusion_mask(width, height, CV_8UC1, cv::Scalar(0));
13551369
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+
}
13561399

13571400
// (4) extract occlusion polygons
13581401
const auto & possible_object_bbox = planner_param_.occlusion.possible_object_bbox;
@@ -1397,19 +1440,11 @@ bool IntersectionModule::isOcclusionCleared(
13971440
}
13981441
// (4.1) re-draw occluded cells using valid_contours
13991442
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) {
14011444
// 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);
14031446
}
14041447

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-
14131448
// (5) find distance
14141449
// (5.1) discretize path_ip with resolution for computational cost
14151450
LineString2d path_linestring;
@@ -1496,7 +1531,11 @@ bool IntersectionModule::isOcclusionCleared(
14961531
const auto [valid, idx_x, idx_y] = coord2index(point_it->x(), point_it->y());
14971532
// TODO(Mamoru Sobue): add handling for blocking vehicles
14981533
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) {
15001539
if (acc_dist < min_dist) {
15011540
min_dist = acc_dist;
15021541
nearest_occlusion_point = {

planning/behavior_velocity_intersection_module/src/util.cpp

+14-5
Original file line numberDiff line numberDiff line change
@@ -1058,17 +1058,18 @@ Polygon2d generateStuckVehicleDetectAreaPolygon(
10581058
}
10591059

10601060
bool checkAngleForTargetLanelets(
1061-
const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets,
1062-
const double detection_area_angle_thr, const bool consider_wrong_direction_vehicle,
1063-
const double margin)
1061+
const geometry_msgs::msg::Pose & pose, const double longitudinal_velocity,
1062+
const lanelet::ConstLanelets & target_lanelets, const double detection_area_angle_thr,
1063+
const bool consider_wrong_direction_vehicle, const double dist_margin,
1064+
const double parked_vehicle_speed_threshold)
10641065
{
10651066
for (const auto & ll : target_lanelets) {
1066-
if (!lanelet::utils::isInLanelet(pose, ll, margin)) {
1067+
if (!lanelet::utils::isInLanelet(pose, ll, dist_margin)) {
10671068
continue;
10681069
}
10691070
const double ll_angle = lanelet::utils::getLaneletAngle(ll, pose.position);
10701071
const double pose_angle = tf2::getYaw(pose.orientation);
1071-
const double angle_diff = tier4_autoware_utils::normalizeRadian(ll_angle - pose_angle);
1072+
const double angle_diff = tier4_autoware_utils::normalizeRadian(ll_angle - pose_angle, -M_PI);
10721073
if (consider_wrong_direction_vehicle) {
10731074
if (std::fabs(angle_diff) > 1.57 || std::fabs(angle_diff) < detection_area_angle_thr) {
10741075
return true;
@@ -1077,6 +1078,14 @@ bool checkAngleForTargetLanelets(
10771078
if (std::fabs(angle_diff) < detection_area_angle_thr) {
10781079
return true;
10791080
}
1081+
// NOTE: sometimes parked vehicle direction is reversed even if its longitudinal velocity is
1082+
// positive
1083+
if (
1084+
std::fabs(longitudinal_velocity) < parked_vehicle_speed_threshold &&
1085+
(std::fabs(angle_diff) < detection_area_angle_thr ||
1086+
(std::fabs(angle_diff + M_PI) < detection_area_angle_thr))) {
1087+
return true;
1088+
}
10801089
}
10811090
}
10821091
return false;

planning/behavior_velocity_intersection_module/src/util.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -136,9 +136,10 @@ Polygon2d generateStuckVehicleDetectAreaPolygon(
136136
const util::PathLanelets & path_lanelets, const double stuck_vehicle_detect_dist);
137137

138138
bool checkAngleForTargetLanelets(
139-
const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets,
140-
const double detection_area_angle_thr, const bool consider_wrong_direction_vehicle,
141-
const double margin = 0.0);
139+
const geometry_msgs::msg::Pose & pose, const double longitudinal_velocity,
140+
const lanelet::ConstLanelets & target_lanelets, const double detection_area_angle_thr,
141+
const bool consider_wrong_direction_vehicle, const double dist_margin,
142+
const double parked_vehicle_speed_threshold);
142143

143144
void cutPredictPathWithDuration(
144145
autoware_auto_perception_msgs::msg::PredictedObjects * objects_ptr,

planning/behavior_velocity_intersection_module/src/util_type.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@ struct DebugData
5050
std::vector<geometry_msgs::msg::Polygon> occlusion_polygons;
5151
std::optional<std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
5252
nearest_occlusion_projection{std::nullopt};
53+
autoware_auto_perception_msgs::msg::PredictedObjects blocking_attention_objects;
5354
};
5455

5556
struct InterpolatedPathInfo

0 commit comments

Comments
 (0)