Skip to content

Commit 6f8edcd

Browse files
committed
perf PR 8109
1 parent 5de95b0 commit 6f8edcd

File tree

2 files changed

+37
-28
lines changed

2 files changed

+37
-28
lines changed

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

+2-6
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,6 @@ class ObjectLaneletFilterNode : public rclcpp::Node
5454
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_{nullptr};
5555

5656
lanelet::LaneletMapPtr lanelet_map_ptr_;
57-
lanelet::ConstLanelets road_lanelets_;
58-
lanelet::ConstLanelets shoulder_lanelets_;
5957
std::string lanelet_frame_id_;
6058

6159
tf2_ros::Buffer tf_buffer_;
@@ -73,12 +71,10 @@ class ObjectLaneletFilterNode : public rclcpp::Node
7371
bool filterObject(
7472
const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object,
7573
const autoware_auto_perception_msgs::msg::DetectedObject & input_object,
76-
const lanelet::ConstLanelets & intersected_road_lanelets,
77-
const lanelet::ConstLanelets & intersected_shoulder_lanelets,
74+
const lanelet::ConstLanelets & intersected_lanelets,
7875
autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg);
7976
LinearRing2d getConvexHull(const autoware_auto_perception_msgs::msg::DetectedObjects &);
80-
lanelet::ConstLanelets getIntersectedLanelets(
81-
const LinearRing2d &, const lanelet::ConstLanelets &);
77+
lanelet::ConstLanelets getIntersectedLanelets(const LinearRing2d &);
8278
bool isObjectOverlapLanelets(
8379
const autoware_auto_perception_msgs::msg::DetectedObject & object,
8480
const lanelet::ConstLanelets & intersected_lanelets);

perception/detected_object_validation/src/object_lanelet_filter.cpp

+35-22
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,8 @@
2323
#include <boost/geometry/algorithms/disjoint.hpp>
2424
#include <boost/geometry/algorithms/intersects.hpp>
2525

26+
#include <lanelet2_core/geometry/BoundingBox.h>
27+
#include <lanelet2_core/geometry/LaneletMap.h>
2628
#include <lanelet2_core/geometry/Polygon.h>
2729

2830
namespace object_lanelet_filter
@@ -72,9 +74,6 @@ void ObjectLaneletFilterNode::mapCallback(
7274
lanelet_frame_id_ = map_msg->header.frame_id;
7375
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
7476
lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_);
75-
const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
76-
road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets);
77-
shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets);
7877
}
7978

8079
void ObjectLaneletFilterNode::objectCallback(
@@ -100,18 +99,13 @@ void ObjectLaneletFilterNode::objectCallback(
10099
// calculate convex hull
101100
const auto convex_hull = getConvexHull(transformed_objects);
102101
// get intersected lanelets
103-
lanelet::ConstLanelets intersected_road_lanelets =
104-
getIntersectedLanelets(convex_hull, road_lanelets_);
105-
lanelet::ConstLanelets intersected_shoulder_lanelets =
106-
getIntersectedLanelets(convex_hull, shoulder_lanelets_);
102+
lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull);
107103

108104
// filtering process
109105
for (size_t index = 0; index < transformed_objects.objects.size(); ++index) {
110106
const auto & transformed_object = transformed_objects.objects.at(index);
111107
const auto & input_object = input_msg->objects.at(index);
112-
filterObject(
113-
transformed_object, input_object, intersected_road_lanelets, intersected_shoulder_lanelets,
114-
output_object_msg);
108+
filterObject(transformed_object, input_object, intersected_lanelets, output_object_msg);
115109
}
116110
object_pub_->publish(output_object_msg);
117111

@@ -128,8 +122,7 @@ void ObjectLaneletFilterNode::objectCallback(
128122
bool ObjectLaneletFilterNode::filterObject(
129123
const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object,
130124
const autoware_auto_perception_msgs::msg::DetectedObject & input_object,
131-
const lanelet::ConstLanelets & intersected_road_lanelets,
132-
const lanelet::ConstLanelets & intersected_shoulder_lanelets,
125+
const lanelet::ConstLanelets & intersected_lanelets,
133126
autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg)
134127
{
135128
const auto & label = transformed_object.classification.front().label;
@@ -138,8 +131,7 @@ bool ObjectLaneletFilterNode::filterObject(
138131
// 1. is polygon overlap with road lanelets or shoulder lanelets
139132
if (filter_settings_.polygon_overlap_filter) {
140133
const bool is_polygon_overlap =
141-
isObjectOverlapLanelets(transformed_object, intersected_road_lanelets) ||
142-
isObjectOverlapLanelets(transformed_object, intersected_shoulder_lanelets);
134+
isObjectOverlapLanelets(transformed_object, intersected_lanelets);
143135
filter_pass = filter_pass && is_polygon_overlap;
144136
}
145137

@@ -149,8 +141,7 @@ bool ObjectLaneletFilterNode::filterObject(
149141
autoware_auto_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE;
150142
if (filter_settings_.lanelet_direction_filter && !orientation_not_available) {
151143
const bool is_same_direction =
152-
isSameDirectionWithLanelets(intersected_road_lanelets, transformed_object) ||
153-
isSameDirectionWithLanelets(intersected_shoulder_lanelets, transformed_object);
144+
isSameDirectionWithLanelets(intersected_lanelets, transformed_object);
154145
filter_pass = filter_pass && is_same_direction;
155146
}
156147

@@ -209,18 +200,40 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull(
209200
return convex_hull;
210201
}
211202

203+
// fetch the intersected candidate lanelets with bounding box and then
204+
// check the intersections among the lanelets and the convex hull
212205
lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets(
213-
const LinearRing2d & convex_hull, const lanelet::ConstLanelets & road_lanelets)
206+
const LinearRing2d & convex_hull)
214207
{
208+
namespace bg = boost::geometry;
215209
lanelet::ConstLanelets intersected_lanelets;
216210

217-
// WARNING: This implementation currently iterate all lanelets, which could degrade performance
218-
// when handling large sized map.
219-
for (const auto & road_lanelet : road_lanelets) {
220-
if (boost::geometry::intersects(convex_hull, road_lanelet.polygon2d().basicPolygon())) {
221-
intersected_lanelets.emplace_back(road_lanelet);
211+
// 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(
215+
lanelet::BasicPoint2d(
216+
bg::get<bg::min_corner, 0>(bbox2d_convex_hull),
217+
bg::get<bg::min_corner, 1>(bbox2d_convex_hull)),
218+
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);
223+
224+
for (const auto & lanelet : candidates_lanelets) {
225+
// only check the road lanelets and road shoulder lanelets
226+
if (
227+
lanelet.hasAttribute(lanelet::AttributeName::Subtype) &&
228+
(lanelet.attribute(lanelet::AttributeName::Subtype).value() ==
229+
lanelet::AttributeValueString::Road ||
230+
lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) {
231+
if (boost::geometry::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) {
232+
intersected_lanelets.emplace_back(lanelet);
233+
}
222234
}
223235
}
236+
224237
return intersected_lanelets;
225238
}
226239

0 commit comments

Comments
 (0)