Skip to content

Commit 0cc85c2

Browse files
committed
chore: refactor lanelet filter function
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 3aa84b0 commit 0cc85c2

File tree

2 files changed

+47
-21
lines changed

2 files changed

+47
-21
lines changed

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

+6
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,12 @@ class ObjectLaneletFilterNode : public rclcpp::Node
6363

6464
utils::FilterTargetLabel filter_target_;
6565

66+
bool filterObject(
67+
const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object,
68+
const autoware_auto_perception_msgs::msg::DetectedObject & input_object,
69+
const lanelet::ConstLanelets & intersected_road_lanelets,
70+
const lanelet::ConstLanelets & intersected_shoulder_lanelets,
71+
autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg);
6672
LinearRing2d getConvexHull(const autoware_auto_perception_msgs::msg::DetectedObjects &);
6773
lanelet::ConstLanelets getIntersectedLanelets(
6874
const LinearRing2d &, const lanelet::ConstLanelets &);

perception/detected_object_validation/src/object_lanelet_filter.cpp

+41-21
Original file line numberDiff line numberDiff line change
@@ -97,27 +97,13 @@ void ObjectLaneletFilterNode::objectCallback(
9797
lanelet::ConstLanelets intersected_shoulder_lanelets =
9898
getIntersectedLanelets(convex_hull, shoulder_lanelets_);
9999

100-
int index = 0;
101-
for (const auto & object : transformed_objects.objects) {
102-
const auto footprint = setFootprint(object);
103-
const auto & label = object.classification.front().label;
104-
if (filter_target_.isTarget(label)) {
105-
Polygon2d polygon;
106-
for (const auto & point : footprint.points) {
107-
const geometry_msgs::msg::Point32 point_transformed =
108-
tier4_autoware_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose);
109-
polygon.outer().emplace_back(point_transformed.x, point_transformed.y);
110-
}
111-
polygon.outer().push_back(polygon.outer().front());
112-
if (isPolygonOverlapLanelets(polygon, intersected_road_lanelets)) {
113-
output_object_msg.objects.emplace_back(input_msg->objects.at(index));
114-
} else if (isPolygonOverlapLanelets(polygon, intersected_shoulder_lanelets)) {
115-
output_object_msg.objects.emplace_back(input_msg->objects.at(index));
116-
}
117-
} else {
118-
output_object_msg.objects.emplace_back(input_msg->objects.at(index));
119-
}
120-
++index;
100+
// filtering process
101+
for (size_t index = 0; index < transformed_objects.objects.size(); ++index) {
102+
const auto & transformed_object = transformed_objects.objects.at(index);
103+
const auto & input_object = input_msg->objects.at(index);
104+
filterObject(
105+
transformed_object, input_object, intersected_road_lanelets, intersected_shoulder_lanelets,
106+
output_object_msg);
121107
}
122108
object_pub_->publish(output_object_msg);
123109
published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp);
@@ -132,6 +118,40 @@ void ObjectLaneletFilterNode::objectCallback(
132118
"debug/pipeline_latency_ms", pipeline_latency);
133119
}
134120

121+
bool ObjectLaneletFilterNode::filterObject(
122+
const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object,
123+
const autoware_auto_perception_msgs::msg::DetectedObject & input_object,
124+
const lanelet::ConstLanelets & intersected_road_lanelets,
125+
const lanelet::ConstLanelets & intersected_shoulder_lanelets,
126+
autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg)
127+
{
128+
const auto & label = transformed_object.classification.front().label;
129+
if (filter_target_.isTarget(label)) {
130+
// 1. is polygon overlap with road lanelets or shoulder lanelets
131+
Polygon2d polygon;
132+
const auto footprint = setFootprint(transformed_object);
133+
for (const auto & point : footprint.points) {
134+
const geometry_msgs::msg::Point32 point_transformed = tier4_autoware_utils::transformPoint(
135+
point, transformed_object.kinematics.pose_with_covariance.pose);
136+
polygon.outer().emplace_back(point_transformed.x, point_transformed.y);
137+
}
138+
polygon.outer().push_back(polygon.outer().front());
139+
const bool is_polygon_overlap =
140+
isPolygonOverlapLanelets(polygon, intersected_road_lanelets) ||
141+
isPolygonOverlapLanelets(polygon, intersected_shoulder_lanelets);
142+
143+
// push back to output object
144+
if (is_polygon_overlap) {
145+
output_object_msg.objects.emplace_back(input_object);
146+
return true;
147+
}
148+
} else {
149+
output_object_msg.objects.emplace_back(input_object);
150+
return true;
151+
}
152+
return false;
153+
}
154+
135155
geometry_msgs::msg::Polygon ObjectLaneletFilterNode::setFootprint(
136156
const autoware_auto_perception_msgs::msg::DetectedObject & detected_object)
137157
{

0 commit comments

Comments
 (0)