@@ -97,27 +97,13 @@ void ObjectLaneletFilterNode::objectCallback(
97
97
lanelet::ConstLanelets intersected_shoulder_lanelets =
98
98
getIntersectedLanelets (convex_hull, shoulder_lanelets_);
99
99
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);
121
107
}
122
108
object_pub_->publish (output_object_msg);
123
109
published_time_publisher_->publish_if_subscribed (object_pub_, output_object_msg.header .stamp );
@@ -132,6 +118,40 @@ void ObjectLaneletFilterNode::objectCallback(
132
118
" debug/pipeline_latency_ms" , pipeline_latency);
133
119
}
134
120
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
+
135
155
geometry_msgs::msg::Polygon ObjectLaneletFilterNode::setFootprint (
136
156
const autoware_auto_perception_msgs::msg::DetectedObject & detected_object)
137
157
{
0 commit comments