22
22
#include < boost/geometry/algorithms/convex_hull.hpp>
23
23
#include < boost/geometry/algorithms/disjoint.hpp>
24
24
#include < boost/geometry/algorithms/intersects.hpp>
25
+ #include < boost/geometry/index/rtree.hpp>
25
26
26
27
#include < lanelet2_core/geometry/BoundingBox.h>
28
+ #include < lanelet2_core/geometry/Lanelet.h>
27
29
#include < lanelet2_core/geometry/LaneletMap.h>
28
30
#include < lanelet2_core/geometry/Polygon.h>
29
31
@@ -96,17 +98,27 @@ void ObjectLaneletFilterNode::objectCallback(
96
98
return ;
97
99
}
98
100
99
- // calculate convex hull
100
- const auto convex_hull = getConvexHull (transformed_objects);
101
- // get intersected lanelets
102
- lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets (convex_hull);
101
+ if (!transformed_objects.objects .empty ()) {
102
+ // calculate convex hull
103
+ const auto convex_hull = getConvexHull (transformed_objects);
103
104
104
- // filtering process
105
- for (size_t index = 0 ; index < transformed_objects.objects .size (); ++index ) {
106
- const auto & transformed_object = transformed_objects.objects .at (index );
107
- const auto & input_object = input_msg->objects .at (index );
108
- filterObject (transformed_object, input_object, intersected_lanelets, output_object_msg);
105
+ // get intersected lanelets
106
+ std::vector<BoxAndLanelet> intersected_lanelets_with_bbox = getIntersectedLanelets (convex_hull);
107
+
108
+ // create R-Tree with intersected_lanelets for fast search
109
+ bgi::rtree<BoxAndLanelet, RtreeAlgo> local_rtree;
110
+ for (const auto & bbox_and_lanelet : intersected_lanelets_with_bbox) {
111
+ local_rtree.insert (bbox_and_lanelet);
112
+ }
113
+
114
+ // filtering process
115
+ for (size_t index = 0 ; index < transformed_objects.objects .size (); ++index ) {
116
+ const auto & transformed_object = transformed_objects.objects .at (index );
117
+ const auto & input_object = input_msg->objects .at (index );
118
+ filterObject (transformed_object, input_object, local_rtree, output_object_msg);
119
+ }
109
120
}
121
+
110
122
object_pub_->publish (output_object_msg);
111
123
112
124
// Publish debug info
@@ -122,16 +134,20 @@ void ObjectLaneletFilterNode::objectCallback(
122
134
bool ObjectLaneletFilterNode::filterObject (
123
135
const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object,
124
136
const autoware_auto_perception_msgs::msg::DetectedObject & input_object,
125
- const lanelet::ConstLanelets & intersected_lanelets ,
137
+ const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree ,
126
138
autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg)
127
139
{
128
140
const auto & label = transformed_object.classification .front ().label ;
129
141
if (filter_target_.isTarget (label)) {
142
+ // no tree, then no intersection
143
+ if (local_rtree.empty ()) {
144
+ return false ;
145
+ }
146
+
130
147
bool filter_pass = true ;
131
148
// 1. is polygon overlap with road lanelets or shoulder lanelets
132
149
if (filter_settings_.polygon_overlap_filter ) {
133
- const bool is_polygon_overlap =
134
- isObjectOverlapLanelets (transformed_object, intersected_lanelets);
150
+ const bool is_polygon_overlap = isObjectOverlapLanelets (transformed_object, local_rtree);
135
151
filter_pass = filter_pass && is_polygon_overlap;
136
152
}
137
153
@@ -140,8 +156,7 @@ bool ObjectLaneletFilterNode::filterObject(
140
156
transformed_object.kinematics .orientation_availability ==
141
157
autoware_auto_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE;
142
158
if (filter_settings_.lanelet_direction_filter && !orientation_not_available) {
143
- const bool is_same_direction =
144
- isSameDirectionWithLanelets (intersected_lanelets, transformed_object);
159
+ const bool is_same_direction = isSameDirectionWithLanelets (transformed_object, local_rtree);
145
160
filter_pass = filter_pass && is_same_direction;
146
161
}
147
162
@@ -195,53 +210,74 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull(
195
210
}
196
211
197
212
LinearRing2d convex_hull;
198
- boost::geometry::convex_hull (candidate_points, convex_hull);
213
+ bg::convex_hull (candidate_points, convex_hull);
214
+
215
+ return convex_hull;
216
+ }
217
+
218
+ LinearRing2d ObjectLaneletFilterNode::getConvexHullFromObjectFootprint (
219
+ const autoware_auto_perception_msgs::msg::DetectedObject & object)
220
+ {
221
+ MultiPoint2d candidate_points;
222
+ const auto & pos = object.kinematics .pose_with_covariance .pose .position ;
223
+ const auto footprint = setFootprint (object);
224
+
225
+ for (const auto & p : footprint.points ) {
226
+ candidate_points.emplace_back (p.x + pos.x , p.y + pos.y );
227
+ }
228
+
229
+ LinearRing2d convex_hull;
230
+ bg::convex_hull (candidate_points, convex_hull);
199
231
200
232
return convex_hull;
201
233
}
202
234
203
235
// fetch the intersected candidate lanelets with bounding box and then
204
236
// check the intersections among the lanelets and the convex hull
205
- lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets (
237
+ std::vector<BoxAndLanelet> ObjectLaneletFilterNode::getIntersectedLanelets (
206
238
const LinearRing2d & convex_hull)
207
239
{
208
- namespace bg = boost::geometry;
209
- lanelet::ConstLanelets intersected_lanelets;
240
+ std::vector<BoxAndLanelet> intersected_lanelets_with_bbox;
210
241
211
242
// convert convex_hull to a 2D bounding box for searching in the LaneletMap
212
- bg::model::box<bg::model::d2::point_xy<double >> bbox2d_convex_hull ;
213
- bg::envelope (convex_hull, bbox2d_convex_hull );
214
- lanelet::BoundingBox2d bbox2d (
243
+ bg::model::box<bg::model::d2::point_xy<double >> bbox_of_convex_hull ;
244
+ bg::envelope (convex_hull, bbox_of_convex_hull );
245
+ const lanelet::BoundingBox2d bbox2d (
215
246
lanelet::BasicPoint2d (
216
- bg::get<bg::min_corner, 0 >(bbox2d_convex_hull ),
217
- bg::get<bg::min_corner, 1 >(bbox2d_convex_hull )),
247
+ bg::get<bg::min_corner, 0 >(bbox_of_convex_hull ),
248
+ bg::get<bg::min_corner, 1 >(bbox_of_convex_hull )),
218
249
lanelet::BasicPoint2d (
219
- bg::get<bg::max_corner, 0 >(bbox2d_convex_hull),
220
- bg::get<bg::max_corner, 1 >(bbox2d_convex_hull)));
221
-
222
- lanelet::Lanelets candidates_lanelets = lanelet_map_ptr_->laneletLayer .search (bbox2d);
250
+ bg::get<bg::max_corner, 0 >(bbox_of_convex_hull),
251
+ bg::get<bg::max_corner, 1 >(bbox_of_convex_hull)));
223
252
224
- for (const auto & lanelet : candidates_lanelets) {
253
+ const lanelet::Lanelets candidate_lanelets = lanelet_map_ptr_->laneletLayer .search (bbox2d);
254
+ for (const auto & lanelet : candidate_lanelets) {
225
255
// only check the road lanelets and road shoulder lanelets
226
256
if (
227
257
lanelet.hasAttribute (lanelet::AttributeName::Subtype) &&
228
258
(lanelet.attribute (lanelet::AttributeName::Subtype).value () ==
229
259
lanelet::AttributeValueString::Road ||
230
260
lanelet.attribute (lanelet::AttributeName::Subtype).value () == " road_shoulder" )) {
231
- if (boost::geometry::intersects (convex_hull, lanelet.polygon2d ().basicPolygon ())) {
232
- intersected_lanelets.emplace_back (lanelet);
261
+ if (bg::intersects (convex_hull, lanelet.polygon2d ().basicPolygon ())) {
262
+ // create bbox using boost for making the R-tree in later phase
263
+ lanelet::BoundingBox2d lanelet_bbox = lanelet::geometry::boundingBox2d (lanelet);
264
+ Point2d min_corner (lanelet_bbox.min ().x (), lanelet_bbox.min ().y ());
265
+ Point2d max_corner (lanelet_bbox.max ().x (), lanelet_bbox.max ().y ());
266
+ Box boost_bbox (min_corner, max_corner);
267
+
268
+ intersected_lanelets_with_bbox.emplace_back (std::make_pair (boost_bbox, lanelet));
233
269
}
234
270
}
235
271
}
236
272
237
- return intersected_lanelets ;
273
+ return intersected_lanelets_with_bbox ;
238
274
}
239
275
240
276
bool ObjectLaneletFilterNode::isObjectOverlapLanelets (
241
277
const autoware_auto_perception_msgs::msg::DetectedObject & object,
242
- const lanelet::ConstLanelets & intersected_lanelets )
278
+ const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree )
243
279
{
244
- // if has bounding box, use polygon overlap
280
+ // if object has bounding box, use polygon overlap
245
281
if (object.shape .type != autoware_auto_perception_msgs::msg::Shape::POLYGON) {
246
282
Polygon2d polygon;
247
283
const auto footprint = setFootprint (object);
@@ -251,39 +287,57 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
251
287
polygon.outer ().emplace_back (point_transformed.x , point_transformed.y );
252
288
}
253
289
polygon.outer ().push_back (polygon.outer ().front ());
254
- return isPolygonOverlapLanelets (polygon, intersected_lanelets);
290
+
291
+ return isPolygonOverlapLanelets (polygon, local_rtree);
255
292
} else {
293
+ const LinearRing2d object_convex_hull = getConvexHullFromObjectFootprint (object);
294
+
295
+ // create bounding box to search in the rtree
296
+ std::vector<BoxAndLanelet> candidates;
297
+ bg::model::box<bg::model::d2::point_xy<double >> bbox;
298
+ bg::envelope (object_convex_hull, bbox);
299
+ local_rtree.query (bgi::intersects (bbox), std::back_inserter (candidates));
300
+
256
301
// if object do not have bounding box, check each footprint is inside polygon
257
302
for (const auto & point : object.shape .footprint .points ) {
258
303
const geometry_msgs::msg::Point32 point_transformed =
259
304
tier4_autoware_utils::transformPoint (point, object.kinematics .pose_with_covariance .pose );
260
305
geometry_msgs::msg::Pose point2d;
261
306
point2d.position .x = point_transformed.x ;
262
307
point2d.position .y = point_transformed.y ;
263
- for (const auto & lanelet : intersected_lanelets) {
264
- if (lanelet::utils::isInLanelet (point2d, lanelet, 0.0 )) {
308
+
309
+ for (const auto & candidate : candidates) {
310
+ if (lanelet::utils::isInLanelet (point2d, candidate.second , 0.0 )) {
265
311
return true ;
266
312
}
267
313
}
268
314
}
315
+
269
316
return false ;
270
317
}
271
318
}
272
319
273
320
bool ObjectLaneletFilterNode::isPolygonOverlapLanelets (
274
- const Polygon2d & polygon, const lanelet::ConstLanelets & intersected_lanelets )
321
+ const Polygon2d & polygon, const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree )
275
322
{
276
- for (const auto & lanelet : intersected_lanelets) {
277
- if (!boost::geometry::disjoint (polygon, lanelet.polygon2d ().basicPolygon ())) {
323
+ // create a bounding box from polygon for searching the local R-tree
324
+ std::vector<BoxAndLanelet> candidates;
325
+ bg::model::box<bg::model::d2::point_xy<double >> bbox_of_convex_hull;
326
+ bg::envelope (polygon, bbox_of_convex_hull);
327
+ local_rtree.query (bgi::intersects (bbox_of_convex_hull), std::back_inserter (candidates));
328
+
329
+ for (const auto & box_and_lanelet : candidates) {
330
+ if (!bg::disjoint (polygon, box_and_lanelet.second .polygon2d ().basicPolygon ())) {
278
331
return true ;
279
332
}
280
333
}
334
+
281
335
return false ;
282
336
}
283
337
284
338
bool ObjectLaneletFilterNode::isSameDirectionWithLanelets (
285
- const lanelet::ConstLanelets & lanelets ,
286
- const autoware_auto_perception_msgs::msg::DetectedObject & object )
339
+ const autoware_auto_perception_msgs::msg::DetectedObject & object ,
340
+ const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree )
287
341
{
288
342
const double object_yaw = tf2::getYaw (object.kinematics .pose_with_covariance .pose .orientation );
289
343
const double object_velocity_norm = std::hypot (
@@ -297,14 +351,30 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
297
351
if (object_velocity_norm < filter_settings_.lanelet_direction_filter_object_speed_threshold ) {
298
352
return true ;
299
353
}
300
- for (const auto & lanelet : lanelets) {
301
- const bool is_in_lanelet =
302
- lanelet::utils::isInLanelet (object.kinematics .pose_with_covariance .pose , lanelet, 0.0 );
354
+
355
+ // we can not query by points, so create a small bounding box
356
+ // eps is not determined by any specific criteria; just a guess
357
+ constexpr double eps = 1.0e-6 ;
358
+ std::vector<BoxAndLanelet> candidates;
359
+ const Point2d min_corner (
360
+ object.kinematics .pose_with_covariance .pose .position .x - eps,
361
+ object.kinematics .pose_with_covariance .pose .position .y - eps);
362
+ const Point2d max_corner (
363
+ object.kinematics .pose_with_covariance .pose .position .x + eps,
364
+ object.kinematics .pose_with_covariance .pose .position .y + eps);
365
+ const Box bbox (min_corner, max_corner);
366
+
367
+ local_rtree.query (bgi::intersects (bbox), std::back_inserter (candidates));
368
+
369
+ for (const auto & box_and_lanelet : candidates) {
370
+ const bool is_in_lanelet = lanelet::utils::isInLanelet (
371
+ object.kinematics .pose_with_covariance .pose , box_and_lanelet.second , 0.0 );
303
372
if (!is_in_lanelet) {
304
373
continue ;
305
374
}
375
+
306
376
const double lane_yaw = lanelet::utils::getLaneletAngle (
307
- lanelet , object.kinematics .pose_with_covariance .pose .position );
377
+ box_and_lanelet. second , object.kinematics .pose_with_covariance .pose .position );
308
378
const double delta_yaw = object_velocity_yaw - lane_yaw;
309
379
const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian (delta_yaw);
310
380
const double abs_norm_delta_yaw = std::fabs (normalized_delta_yaw);
0 commit comments