Skip to content

Commit a1a22a6

Browse files
a-maumaupre-commit-ci[bot]technolojin
authored
perf(autoware_detected_object_validation): reduce lanelet_filter processing time (autowarefoundation#8240)
* add local r-tree for fast searching Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> change to _func__ add more debug use local rtree fix tmp update fix bug clean unused clean up Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> * clean up Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> * 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: Taekjin LEE <taekjin.lee@tier4.jp> --------- 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> Co-authored-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent f48336c commit a1a22a6

File tree

2 files changed

+135
-51
lines changed

2 files changed

+135
-51
lines changed

perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

+114-45
Original file line numberDiff line numberDiff line change
@@ -15,15 +15,18 @@
1515
#include "lanelet_filter.hpp"
1616

1717
#include "autoware/universe_utils/geometry/geometry.hpp"
18+
#include "autoware/universe_utils/system/time_keeper.hpp"
1819
#include "autoware_lanelet2_extension/utility/message_conversion.hpp"
1920
#include "autoware_lanelet2_extension/utility/query.hpp"
2021
#include "object_recognition_utils/object_recognition_utils.hpp"
2122

2223
#include <boost/geometry/algorithms/convex_hull.hpp>
2324
#include <boost/geometry/algorithms/disjoint.hpp>
2425
#include <boost/geometry/algorithms/intersects.hpp>
26+
#include <boost/geometry/index/rtree.hpp>
2527

2628
#include <lanelet2_core/geometry/BoundingBox.h>
29+
#include <lanelet2_core/geometry/Lanelet.h>
2730
#include <lanelet2_core/geometry/LaneletMap.h>
2831
#include <lanelet2_core/geometry/Polygon.h>
2932

@@ -100,18 +103,27 @@ void ObjectLaneletFilterNode::objectCallback(
100103
return;
101104
}
102105

103-
// calculate convex hull
104-
const auto convex_hull = getConvexHull(transformed_objects);
106+
if (!transformed_objects.objects.empty()) {
107+
// calculate convex hull
108+
const auto convex_hull = getConvexHull(transformed_objects);
105109

106-
// get intersected lanelets
107-
lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull);
110+
// get intersected lanelets
111+
std::vector<BoxAndLanelet> intersected_lanelets_with_bbox = getIntersectedLanelets(convex_hull);
108112

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

@@ -128,16 +140,20 @@ void ObjectLaneletFilterNode::objectCallback(
128140
bool ObjectLaneletFilterNode::filterObject(
129141
const autoware_perception_msgs::msg::DetectedObject & transformed_object,
130142
const autoware_perception_msgs::msg::DetectedObject & input_object,
131-
const lanelet::ConstLanelets & intersected_lanelets,
143+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree,
132144
autoware_perception_msgs::msg::DetectedObjects & output_object_msg)
133145
{
134146
const auto & label = transformed_object.classification.front().label;
135147
if (filter_target_.isTarget(label)) {
148+
// no tree, then no intersection
149+
if (local_rtree.empty()) {
150+
return false;
151+
}
152+
136153
bool filter_pass = true;
137154
// 1. is polygon overlap with road lanelets or shoulder lanelets
138155
if (filter_settings_.polygon_overlap_filter) {
139-
const bool is_polygon_overlap =
140-
isObjectOverlapLanelets(transformed_object, intersected_lanelets);
156+
const bool is_polygon_overlap = isObjectOverlapLanelets(transformed_object, local_rtree);
141157
filter_pass = filter_pass && is_polygon_overlap;
142158
}
143159

@@ -146,8 +162,7 @@ bool ObjectLaneletFilterNode::filterObject(
146162
transformed_object.kinematics.orientation_availability ==
147163
autoware_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE;
148164
if (filter_settings_.lanelet_direction_filter && !orientation_not_available) {
149-
const bool is_same_direction =
150-
isSameDirectionWithLanelets(intersected_lanelets, transformed_object);
165+
const bool is_same_direction = isSameDirectionWithLanelets(transformed_object, local_rtree);
151166
filter_pass = filter_pass && is_same_direction;
152167
}
153168

@@ -199,55 +214,75 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull(
199214
candidate_points.emplace_back(p.x + pos.x, p.y + pos.y);
200215
}
201216
}
217+
LinearRing2d convex_hull;
218+
bg::convex_hull(candidate_points, convex_hull);
219+
220+
return convex_hull;
221+
}
222+
223+
LinearRing2d ObjectLaneletFilterNode::getConvexHullFromObjectFootprint(
224+
const autoware_perception_msgs::msg::DetectedObject & object)
225+
{
226+
MultiPoint2d candidate_points;
227+
const auto & pos = object.kinematics.pose_with_covariance.pose.position;
228+
const auto footprint = setFootprint(object);
229+
230+
for (const auto & p : footprint.points) {
231+
candidate_points.emplace_back(p.x + pos.x, p.y + pos.y);
232+
}
202233

203234
LinearRing2d convex_hull;
204-
boost::geometry::convex_hull(candidate_points, convex_hull);
235+
bg::convex_hull(candidate_points, convex_hull);
205236

206237
return convex_hull;
207238
}
208239

209240
// fetch the intersected candidate lanelets with bounding box and then
210241
// check the intersections among the lanelets and the convex hull
211-
lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets(
242+
std::vector<BoxAndLanelet> ObjectLaneletFilterNode::getIntersectedLanelets(
212243
const LinearRing2d & convex_hull)
213244
{
214-
namespace bg = boost::geometry;
215-
216-
lanelet::ConstLanelets intersected_lanelets;
245+
std::vector<BoxAndLanelet> intersected_lanelets_with_bbox;
217246

218247
// convert convex_hull to a 2D bounding box for searching in the LaneletMap
219-
bg::model::box<bg::model::d2::point_xy<double>> bbox2d_convex_hull;
220-
bg::envelope(convex_hull, bbox2d_convex_hull);
221-
lanelet::BoundingBox2d bbox2d(
248+
bg::model::box<bg::model::d2::point_xy<double>> bbox_of_convex_hull;
249+
bg::envelope(convex_hull, bbox_of_convex_hull);
250+
const lanelet::BoundingBox2d bbox2d(
222251
lanelet::BasicPoint2d(
223-
bg::get<bg::min_corner, 0>(bbox2d_convex_hull),
224-
bg::get<bg::min_corner, 1>(bbox2d_convex_hull)),
252+
bg::get<bg::min_corner, 0>(bbox_of_convex_hull),
253+
bg::get<bg::min_corner, 1>(bbox_of_convex_hull)),
225254
lanelet::BasicPoint2d(
226-
bg::get<bg::max_corner, 0>(bbox2d_convex_hull),
227-
bg::get<bg::max_corner, 1>(bbox2d_convex_hull)));
255+
bg::get<bg::max_corner, 0>(bbox_of_convex_hull),
256+
bg::get<bg::max_corner, 1>(bbox_of_convex_hull)));
228257

229-
lanelet::Lanelets candidates_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d);
230-
for (const auto & lanelet : candidates_lanelets) {
258+
const lanelet::Lanelets candidate_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d);
259+
for (const auto & lanelet : candidate_lanelets) {
231260
// only check the road lanelets and road shoulder lanelets
232261
if (
233262
lanelet.hasAttribute(lanelet::AttributeName::Subtype) &&
234263
(lanelet.attribute(lanelet::AttributeName::Subtype).value() ==
235264
lanelet::AttributeValueString::Road ||
236265
lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) {
237-
if (boost::geometry::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) {
238-
intersected_lanelets.emplace_back(lanelet);
266+
if (bg::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) {
267+
// create bbox using boost for making the R-tree in later phase
268+
lanelet::BoundingBox2d lanelet_bbox = lanelet::geometry::boundingBox2d(lanelet);
269+
Point2d min_corner(lanelet_bbox.min().x(), lanelet_bbox.min().y());
270+
Point2d max_corner(lanelet_bbox.max().x(), lanelet_bbox.max().y());
271+
Box boost_bbox(min_corner, max_corner);
272+
273+
intersected_lanelets_with_bbox.emplace_back(std::make_pair(boost_bbox, lanelet));
239274
}
240275
}
241276
}
242277

243-
return intersected_lanelets;
278+
return intersected_lanelets_with_bbox;
244279
}
245280

246281
bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
247282
const autoware_perception_msgs::msg::DetectedObject & object,
248-
const lanelet::ConstLanelets & intersected_lanelets)
283+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree)
249284
{
250-
// if has bounding box, use polygon overlap
285+
// if object has bounding box, use polygon overlap
251286
if (utils::hasBoundingBox(object)) {
252287
Polygon2d polygon;
253288
const auto footprint = setFootprint(object);
@@ -258,8 +293,17 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
258293
polygon.outer().emplace_back(point_transformed.x, point_transformed.y);
259294
}
260295
polygon.outer().push_back(polygon.outer().front());
261-
return isPolygonOverlapLanelets(polygon, intersected_lanelets);
296+
297+
return isPolygonOverlapLanelets(polygon, local_rtree);
262298
} else {
299+
const LinearRing2d object_convex_hull = getConvexHullFromObjectFootprint(object);
300+
301+
// create bounding box to search in the rtree
302+
std::vector<BoxAndLanelet> candidates;
303+
bg::model::box<bg::model::d2::point_xy<double>> bbox;
304+
bg::envelope(object_convex_hull, bbox);
305+
local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates));
306+
263307
// if object do not have bounding box, check each footprint is inside polygon
264308
for (const auto & point : object.shape.footprint.points) {
265309
const geometry_msgs::msg::Point32 point_transformed =
@@ -268,30 +312,39 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets(
268312
geometry_msgs::msg::Pose point2d;
269313
point2d.position.x = point_transformed.x;
270314
point2d.position.y = point_transformed.y;
271-
for (const auto & lanelet : intersected_lanelets) {
272-
if (lanelet::utils::isInLanelet(point2d, lanelet, 0.0)) {
315+
316+
for (const auto & candidate : candidates) {
317+
if (lanelet::utils::isInLanelet(point2d, candidate.second, 0.0)) {
273318
return true;
274319
}
275320
}
276321
}
322+
277323
return false;
278324
}
279325
}
280326

281327
bool ObjectLaneletFilterNode::isPolygonOverlapLanelets(
282-
const Polygon2d & polygon, const lanelet::ConstLanelets & intersected_lanelets)
328+
const Polygon2d & polygon, const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree)
283329
{
284-
for (const auto & lanelet : intersected_lanelets) {
285-
if (!boost::geometry::disjoint(polygon, lanelet.polygon2d().basicPolygon())) {
330+
// create a bounding box from polygon for searching the local R-tree
331+
std::vector<BoxAndLanelet> candidates;
332+
bg::model::box<bg::model::d2::point_xy<double>> bbox_of_convex_hull;
333+
bg::envelope(polygon, bbox_of_convex_hull);
334+
local_rtree.query(bgi::intersects(bbox_of_convex_hull), std::back_inserter(candidates));
335+
336+
for (const auto & box_and_lanelet : candidates) {
337+
if (!bg::disjoint(polygon, box_and_lanelet.second.polygon2d().basicPolygon())) {
286338
return true;
287339
}
288340
}
341+
289342
return false;
290343
}
291344

292345
bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
293-
const lanelet::ConstLanelets & lanelets,
294-
const autoware_perception_msgs::msg::DetectedObject & object)
346+
const autoware_perception_msgs::msg::DetectedObject & object,
347+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree)
295348
{
296349
const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation);
297350
const double object_velocity_norm = std::hypot(
@@ -305,14 +358,30 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
305358
if (object_velocity_norm < filter_settings_.lanelet_direction_filter_object_speed_threshold) {
306359
return true;
307360
}
308-
for (const auto & lanelet : lanelets) {
309-
const bool is_in_lanelet =
310-
lanelet::utils::isInLanelet(object.kinematics.pose_with_covariance.pose, lanelet, 0.0);
361+
362+
// we can not query by points, so create a small bounding box
363+
// eps is not determined by any specific criteria; just a guess
364+
constexpr double eps = 1.0e-6;
365+
std::vector<BoxAndLanelet> candidates;
366+
const Point2d min_corner(
367+
object.kinematics.pose_with_covariance.pose.position.x - eps,
368+
object.kinematics.pose_with_covariance.pose.position.y - eps);
369+
const Point2d max_corner(
370+
object.kinematics.pose_with_covariance.pose.position.x + eps,
371+
object.kinematics.pose_with_covariance.pose.position.y + eps);
372+
const Box bbox(min_corner, max_corner);
373+
374+
local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates));
375+
376+
for (const auto & box_and_lanelet : candidates) {
377+
const bool is_in_lanelet = lanelet::utils::isInLanelet(
378+
object.kinematics.pose_with_covariance.pose, box_and_lanelet.second, 0.0);
311379
if (!is_in_lanelet) {
312380
continue;
313381
}
382+
314383
const double lane_yaw = lanelet::utils::getLaneletAngle(
315-
lanelet, object.kinematics.pose_with_covariance.pose.position);
384+
box_and_lanelet.second, object.kinematics.pose_with_covariance.pose.position);
316385
const double delta_yaw = object_velocity_yaw - lane_yaw;
317386
const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw);
318387
const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw);

perception/autoware_detected_object_validation/src/lanelet_filter/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 autoware::detected_object_validation
3742
{
@@ -42,6 +47,13 @@ using autoware::universe_utils::MultiPoint2d;
4247
using autoware::universe_utils::Point2d;
4348
using autoware::universe_utils::Polygon2d;
4449

50+
namespace bg = boost::geometry;
51+
namespace bgi = boost::geometry::index;
52+
using Point2d = bg::model::point<double, 2, bg::cs::cartesian>;
53+
using Box = boost::geometry::model::box<Point2d>;
54+
using BoxAndLanelet = std::pair<Box, lanelet::Lanelet>;
55+
using RtreeAlgo = bgi::rstar<16>;
56+
4557
class ObjectLaneletFilterNode : public rclcpp::Node
4658
{
4759
public:
@@ -74,17 +86,20 @@ class ObjectLaneletFilterNode : public rclcpp::Node
7486
bool filterObject(
7587
const autoware_perception_msgs::msg::DetectedObject & transformed_object,
7688
const autoware_perception_msgs::msg::DetectedObject & input_object,
77-
const lanelet::ConstLanelets & intersected_lanelets,
89+
const bg::index::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree,
7890
autoware_perception_msgs::msg::DetectedObjects & output_object_msg);
7991
LinearRing2d getConvexHull(const autoware_perception_msgs::msg::DetectedObjects &);
80-
lanelet::ConstLanelets getIntersectedLanelets(const LinearRing2d &);
92+
LinearRing2d getConvexHullFromObjectFootprint(
93+
const autoware_perception_msgs::msg::DetectedObject & object);
94+
std::vector<BoxAndLanelet> getIntersectedLanelets(const LinearRing2d &);
8195
bool isObjectOverlapLanelets(
8296
const autoware_perception_msgs::msg::DetectedObject & object,
83-
const lanelet::ConstLanelets & intersected_lanelets);
84-
bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &);
97+
const bg::index::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree);
98+
bool isPolygonOverlapLanelets(
99+
const Polygon2d & polygon, const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree);
85100
bool isSameDirectionWithLanelets(
86-
const lanelet::ConstLanelets & lanelets,
87-
const autoware_perception_msgs::msg::DetectedObject & object);
101+
const autoware_perception_msgs::msg::DetectedObject & object,
102+
const bgi::rtree<BoxAndLanelet, RtreeAlgo> & local_rtree);
88103
geometry_msgs::msg::Polygon setFootprint(const autoware_perception_msgs::msg::DetectedObject &);
89104

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

0 commit comments

Comments
 (0)