Skip to content

Commit a1e97cb

Browse files
perf(autoware_detected_object_validation): reduce lanelet_filter processing time (autowarefoundation#8240) (#1433)
* add local r-tree for fast searching change to _func__ add more debug use local rtree fix tmp update fix bug clean unused clean up * clean up * style(pre-commit): autofix * chore: Optimize object filtering and improve performance The code changes in `lanelet_filter.cpp` optimize the object filtering process by using the `empty()` function instead of checking the size of the `transformed_objects.objects` vector. This change improves performance and simplifies the code logic. Refactor the code to use `empty()` instead of `size()` for checking if the `transformed_objects.objects` vector is empty. This change improves readability and performance. --------- Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 622d6e3 commit a1e97cb

File tree

2 files changed

+134
-51
lines changed

2 files changed

+134
-51
lines changed

perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp

+21-6
Original file line numberDiff line numberDiff line change
@@ -26,12 +26,17 @@
2626
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
2727
#include <autoware_perception_msgs/msg/detected_objects.hpp>
2828

29+
#include <boost/geometry/index/rtree.hpp>
30+
2931
#include <lanelet2_core/Forward.h>
32+
#include <lanelet2_core/geometry/Lanelet.h>
3033
#include <tf2_ros/buffer.h>
3134
#include <tf2_ros/transform_listener.h>
3235

3336
#include <memory>
3437
#include <string>
38+
#include <utility>
39+
#include <vector>
3540

3641
namespace object_lanelet_filter
3742
{
@@ -40,6 +45,13 @@ using autoware::universe_utils::MultiPoint2d;
4045
using autoware::universe_utils::Point2d;
4146
using autoware::universe_utils::Polygon2d;
4247

48+
namespace bg = boost::geometry;
49+
namespace bgi = boost::geometry::index;
50+
using Point2d = bg::model::point<double, 2, bg::cs::cartesian>;
51+
using Box = boost::geometry::model::box<Point2d>;
52+
using BoxAndLanelet = std::pair<Box, lanelet::Lanelet>;
53+
using RtreeAlgo = bgi::rstar<16>;
54+
4355
class ObjectLaneletFilterNode : public rclcpp::Node
4456
{
4557
public:
@@ -72,17 +84,20 @@ class ObjectLaneletFilterNode : public rclcpp::Node
7284
bool filterObject(
7385
const autoware_perception_msgs::msg::DetectedObject & transformed_object,
7486
const autoware_perception_msgs::msg::DetectedObject & input_object,
75-
const lanelet::ConstLanelets & intersected_lanelets,
87+
const bg::index::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree,
7688
autoware_perception_msgs::msg::DetectedObjects & output_object_msg);
7789
LinearRing2d getConvexHull(const autoware_perception_msgs::msg::DetectedObjects &);
78-
lanelet::ConstLanelets getIntersectedLanelets(const LinearRing2d &);
90+
LinearRing2d getConvexHullFromObjectFootprint(
91+
const autoware_perception_msgs::msg::DetectedObject & object);
92+
std::vector<BoxAndLanelet> getIntersectedLanelets(const LinearRing2d &);
7993
bool isObjectOverlapLanelets(
8094
const autoware_perception_msgs::msg::DetectedObject & object,
81-
const lanelet::ConstLanelets & intersected_lanelets);
82-
bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &);
95+
const bg::index::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree);
96+
bool isPolygonOverlapLanelets(
97+
const Polygon2d & polygon, const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree);
8398
bool isSameDirectionWithLanelets(
84-
const lanelet::ConstLanelets & lanelets,
85-
const autoware_perception_msgs::msg::DetectedObject & object);
99+
const autoware_perception_msgs::msg::DetectedObject & object,
100+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree);
86101
geometry_msgs::msg::Polygon setFootprint(const autoware_perception_msgs::msg::DetectedObject &);
87102

88103
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;

perception/detected_object_validation/src/object_lanelet_filter.cpp

+113-45
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,10 @@
2222
#include <boost/geometry/algorithms/convex_hull.hpp>
2323
#include <boost/geometry/algorithms/disjoint.hpp>
2424
#include <boost/geometry/algorithms/intersects.hpp>
25+
#include <boost/geometry/index/rtree.hpp>
2526

2627
#include <lanelet2_core/geometry/BoundingBox.h>
28+
#include <lanelet2_core/geometry/Lanelet.h>
2729
#include <lanelet2_core/geometry/LaneletMap.h>
2830
#include <lanelet2_core/geometry/Polygon.h>
2931

@@ -98,18 +100,27 @@ void ObjectLaneletFilterNode::objectCallback(
98100
return;
99101
}
100102

101-
// calculate convex hull
102-
const auto convex_hull = getConvexHull(transformed_objects);
103+
if (!transformed_objects.objects.empty()) {
104+
// calculate convex hull
105+
const auto convex_hull = getConvexHull(transformed_objects);
103106

104-
// get intersected lanelets
105-
lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull);
107+
// get intersected lanelets
108+
std::vector<BoxAndLanelet> intersected_lanelets_with_bbox = getIntersectedLanelets(convex_hull);
106109

107-
// filtering process
108-
for (size_t index = 0; index < transformed_objects.objects.size(); ++index) {
109-
const auto & transformed_object = transformed_objects.objects.at(index);
110-
const auto & input_object = input_msg->objects.at(index);
111-
filterObject(transformed_object, input_object, intersected_lanelets, output_object_msg);
110+
// create R-Tree with intersected_lanelets for fast search
111+
bgi::rtree<BoxAndLanelet, RtreeAlgo> local_rtree;
112+
for (const auto & bbox_and_lanelet : intersected_lanelets_with_bbox) {
113+
local_rtree.insert(bbox_and_lanelet);
114+
}
115+
116+
// filtering process
117+
for (size_t index = 0; index < transformed_objects.objects.size(); ++index) {
118+
const auto & transformed_object = transformed_objects.objects.at(index);
119+
const auto & input_object = input_msg->objects.at(index);
120+
filterObject(transformed_object, input_object, local_rtree, output_object_msg);
121+
}
112122
}
123+
113124
object_pub_->publish(output_object_msg);
114125
published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp);
115126

@@ -126,16 +137,20 @@ void ObjectLaneletFilterNode::objectCallback(
126137
bool ObjectLaneletFilterNode::filterObject(
127138
const autoware_perception_msgs::msg::DetectedObject & transformed_object,
128139
const autoware_perception_msgs::msg::DetectedObject & input_object,
129-
const lanelet::ConstLanelets & intersected_lanelets,
140+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree,
130141
autoware_perception_msgs::msg::DetectedObjects & output_object_msg)
131142
{
132143
const auto & label = transformed_object.classification.front().label;
133144
if (filter_target_.isTarget(label)) {
145+
// no tree, then no intersection
146+
if (local_rtree.empty()) {
147+
return false;
148+
}
149+
134150
bool filter_pass = true;
135151
// 1. is polygon overlap with road lanelets or shoulder lanelets
136152
if (filter_settings_.polygon_overlap_filter) {
137-
const bool is_polygon_overlap =
138-
isObjectOverlapLanelets(transformed_object, intersected_lanelets);
153+
const bool is_polygon_overlap = isObjectOverlapLanelets(transformed_object, local_rtree);
139154
filter_pass = filter_pass && is_polygon_overlap;
140155
}
141156

@@ -144,8 +159,7 @@ bool ObjectLaneletFilterNode::filterObject(
144159
transformed_object.kinematics.orientation_availability ==
145160
autoware_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE;
146161
if (filter_settings_.lanelet_direction_filter && !orientation_not_available) {
147-
const bool is_same_direction =
148-
isSameDirectionWithLanelets(intersected_lanelets, transformed_object);
162+
const bool is_same_direction = isSameDirectionWithLanelets(transformed_object, local_rtree);
149163
filter_pass = filter_pass && is_same_direction;
150164
}
151165

@@ -197,55 +211,75 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull(
197211
candidate_points.emplace_back(p.x + pos.x, p.y + pos.y);
198212
}
199213
}
214+
LinearRing2d convex_hull;
215+
bg::convex_hull(candidate_points, convex_hull);
216+
217+
return convex_hull;
218+
}
219+
220+
LinearRing2d ObjectLaneletFilterNode::getConvexHullFromObjectFootprint(
221+
const autoware_perception_msgs::msg::DetectedObject & object)
222+
{
223+
MultiPoint2d candidate_points;
224+
const auto & pos = object.kinematics.pose_with_covariance.pose.position;
225+
const auto footprint = setFootprint(object);
226+
227+
for (const auto & p : footprint.points) {
228+
candidate_points.emplace_back(p.x + pos.x, p.y + pos.y);
229+
}
200230

201231
LinearRing2d convex_hull;
202-
boost::geometry::convex_hull(candidate_points, convex_hull);
232+
bg::convex_hull(candidate_points, convex_hull);
203233

204234
return convex_hull;
205235
}
206236

207237
// fetch the intersected candidate lanelets with bounding box and then
208238
// check the intersections among the lanelets and the convex hull
209-
lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets(
239+
std::vector<BoxAndLanelet> ObjectLaneletFilterNode::getIntersectedLanelets(
210240
const LinearRing2d & convex_hull)
211241
{
212-
namespace bg = boost::geometry;
213-
214-
lanelet::ConstLanelets intersected_lanelets;
242+
std::vector<BoxAndLanelet> intersected_lanelets_with_bbox;
215243

216244
// convert convex_hull to a 2D bounding box for searching in the LaneletMap
217-
bg::model::box<bg::model::d2::point_xy<double>> bbox2d_convex_hull;
218-
bg::envelope(convex_hull, bbox2d_convex_hull);
219-
lanelet::BoundingBox2d bbox2d(
245+
bg::model::box<bg::model::d2::point_xy<double>> bbox_of_convex_hull;
246+
bg::envelope(convex_hull, bbox_of_convex_hull);
247+
const lanelet::BoundingBox2d bbox2d(
220248
lanelet::BasicPoint2d(
221-
bg::get<bg::min_corner, 0>(bbox2d_convex_hull),
222-
bg::get<bg::min_corner, 1>(bbox2d_convex_hull)),
249+
bg::get<bg::min_corner, 0>(bbox_of_convex_hull),
250+
bg::get<bg::min_corner, 1>(bbox_of_convex_hull)),
223251
lanelet::BasicPoint2d(
224-
bg::get<bg::max_corner, 0>(bbox2d_convex_hull),
225-
bg::get<bg::max_corner, 1>(bbox2d_convex_hull)));
252+
bg::get<bg::max_corner, 0>(bbox_of_convex_hull),
253+
bg::get<bg::max_corner, 1>(bbox_of_convex_hull)));
226254

227-
lanelet::Lanelets candidates_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d);
228-
for (const auto & lanelet : candidates_lanelets) {
255+
const lanelet::Lanelets candidate_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d);
256+
for (const auto & lanelet : candidate_lanelets) {
229257
// only check the road lanelets and road shoulder lanelets
230258
if (
231259
lanelet.hasAttribute(lanelet::AttributeName::Subtype) &&
232260
(lanelet.attribute(lanelet::AttributeName::Subtype).value() ==
233261
lanelet::AttributeValueString::Road ||
234262
lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) {
235-
if (boost::geometry::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) {
236-
intersected_lanelets.emplace_back(lanelet);
263+
if (bg::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) {
264+
// create bbox using boost for making the R-tree in later phase
265+
lanelet::BoundingBox2d lanelet_bbox = lanelet::geometry::boundingBox2d(lanelet);
266+
Point2d min_corner(lanelet_bbox.min().x(), lanelet_bbox.min().y());
267+
Point2d max_corner(lanelet_bbox.max().x(), lanelet_bbox.max().y());
268+
Box boost_bbox(min_corner, max_corner);
269+
270+
intersected_lanelets_with_bbox.emplace_back(std::make_pair(boost_bbox, lanelet));
237271
}
238272
}
239273
}
240274

241-
return intersected_lanelets;
275+
return intersected_lanelets_with_bbox;
242276
}
243277

244278
bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
245279
const autoware_perception_msgs::msg::DetectedObject & object,
246-
const lanelet::ConstLanelets & intersected_lanelets)
280+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree)
247281
{
248-
// if has bounding box, use polygon overlap
282+
// if object has bounding box, use polygon overlap
249283
if (utils::hasBoundingBox(object)) {
250284
Polygon2d polygon;
251285
const auto footprint = setFootprint(object);
@@ -256,8 +290,17 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
256290
polygon.outer().emplace_back(point_transformed.x, point_transformed.y);
257291
}
258292
polygon.outer().push_back(polygon.outer().front());
259-
return isPolygonOverlapLanelets(polygon, intersected_lanelets);
293+
294+
return isPolygonOverlapLanelets(polygon, local_rtree);
260295
} else {
296+
const LinearRing2d object_convex_hull = getConvexHullFromObjectFootprint(object);
297+
298+
// create bounding box to search in the rtree
299+
std::vector<BoxAndLanelet> candidates;
300+
bg::model::box<bg::model::d2::point_xy<double>> bbox;
301+
bg::envelope(object_convex_hull, bbox);
302+
local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates));
303+
261304
// if object do not have bounding box, check each footprint is inside polygon
262305
for (const auto & point : object.shape.footprint.points) {
263306
const geometry_msgs::msg::Point32 point_transformed =
@@ -266,30 +309,39 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
266309
geometry_msgs::msg::Pose point2d;
267310
point2d.position.x = point_transformed.x;
268311
point2d.position.y = point_transformed.y;
269-
for (const auto & lanelet : intersected_lanelets) {
270-
if (lanelet::utils::isInLanelet(point2d, lanelet, 0.0)) {
312+
313+
for (const auto & candidate : candidates) {
314+
if (lanelet::utils::isInLanelet(point2d, candidate.second, 0.0)) {
271315
return true;
272316
}
273317
}
274318
}
319+
275320
return false;
276321
}
277322
}
278323

279324
bool ObjectLaneletFilterNode::isPolygonOverlapLanelets(
280-
const Polygon2d & polygon, const lanelet::ConstLanelets & intersected_lanelets)
325+
const Polygon2d & polygon, const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree)
281326
{
282-
for (const auto & lanelet : intersected_lanelets) {
283-
if (!boost::geometry::disjoint(polygon, lanelet.polygon2d().basicPolygon())) {
327+
// create a bounding box from polygon for searching the local R-tree
328+
std::vector<BoxAndLanelet> candidates;
329+
bg::model::box<bg::model::d2::point_xy<double>> bbox_of_convex_hull;
330+
bg::envelope(polygon, bbox_of_convex_hull);
331+
local_rtree.query(bgi::intersects(bbox_of_convex_hull), std::back_inserter(candidates));
332+
333+
for (const auto & box_and_lanelet : candidates) {
334+
if (!bg::disjoint(polygon, box_and_lanelet.second.polygon2d().basicPolygon())) {
284335
return true;
285336
}
286337
}
338+
287339
return false;
288340
}
289341

290342
bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
291-
const lanelet::ConstLanelets & lanelets,
292-
const autoware_perception_msgs::msg::DetectedObject & object)
343+
const autoware_perception_msgs::msg::DetectedObject & object,
344+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree)
293345
{
294346
const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation);
295347
const double object_velocity_norm = std::hypot(
@@ -303,14 +355,30 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
303355
if (object_velocity_norm < filter_settings_.lanelet_direction_filter_object_speed_threshold) {
304356
return true;
305357
}
306-
for (const auto & lanelet : lanelets) {
307-
const bool is_in_lanelet =
308-
lanelet::utils::isInLanelet(object.kinematics.pose_with_covariance.pose, lanelet, 0.0);
358+
359+
// we can not query by points, so create a small bounding box
360+
// eps is not determined by any specific criteria; just a guess
361+
constexpr double eps = 1.0e-6;
362+
std::vector<BoxAndLanelet> candidates;
363+
const Point2d min_corner(
364+
object.kinematics.pose_with_covariance.pose.position.x - eps,
365+
object.kinematics.pose_with_covariance.pose.position.y - eps);
366+
const Point2d max_corner(
367+
object.kinematics.pose_with_covariance.pose.position.x + eps,
368+
object.kinematics.pose_with_covariance.pose.position.y + eps);
369+
const Box bbox(min_corner, max_corner);
370+
371+
local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates));
372+
373+
for (const auto & box_and_lanelet : candidates) {
374+
const bool is_in_lanelet = lanelet::utils::isInLanelet(
375+
object.kinematics.pose_with_covariance.pose, box_and_lanelet.second, 0.0);
309376
if (!is_in_lanelet) {
310377
continue;
311378
}
379+
312380
const double lane_yaw = lanelet::utils::getLaneletAngle(
313-
lanelet, object.kinematics.pose_with_covariance.pose.position);
381+
box_and_lanelet.second, object.kinematics.pose_with_covariance.pose.position);
314382
const double delta_yaw = object_velocity_yaw - lane_yaw;
315383
const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw);
316384
const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw);

0 commit comments

Comments
 (0)