@@ -33,8 +33,7 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
33
33
using tier4_autoware_utils::StopWatch;
34
34
stop_watch_ptr_ = std::make_unique<StopWatch<std::chrono::milliseconds>>();
35
35
debug_publisher_ = std::make_unique<DebugPublisher>(this , " ring_outlier_filter" );
36
- excluded_points_publisher_ =
37
- this ->create_publisher <sensor_msgs::msg::PointCloud2>(" debug/ring_outlier_filter" , 1 );
36
+ noise_points_publisher_ = this ->create_publisher <PointCloud2>(" noise/ring_outlier_filter" , 1 );
38
37
stop_watch_ptr_->tic (" cyclic_time" );
39
38
stop_watch_ptr_->tic (" processing_time" );
40
39
}
@@ -48,8 +47,7 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
48
47
max_rings_num_ = static_cast <uint16_t >(declare_parameter (" max_rings_num" , 128 ));
49
48
max_points_num_per_ring_ =
50
49
static_cast <size_t >(declare_parameter (" max_points_num_per_ring" , 4000 ));
51
- publish_excluded_points_ =
52
- static_cast <bool >(declare_parameter (" publish_excluded_points" , false ));
50
+ publish_noise_points_ = static_cast <bool >(declare_parameter (" publish_noise_points" , false ));
53
51
}
54
52
55
53
using std::placeholders::_1;
@@ -73,6 +71,14 @@ void RingOutlierFilterComponent::faster_filter(
73
71
output.data .resize (output.point_step * input->width );
74
72
size_t output_size = 0 ;
75
73
74
+ // Set up the noise points cloud, if noise points are to be published.
75
+ PointCloud2 noise_points;
76
+ size_t noise_points_size = 0 ;
77
+ if (publish_noise_points_) {
78
+ noise_points.point_step = sizeof (PointXYZI);
79
+ noise_points.data .resize (noise_points.point_step * input->width );
80
+ }
81
+
76
82
const auto ring_offset =
77
83
input->fields .at (static_cast <size_t >(autoware_point_types::PointIndex::Ring)).offset ;
78
84
const auto azimuth_offset =
@@ -153,6 +159,26 @@ void RingOutlierFilterComponent::faster_filter(
153
159
154
160
output_size += output.point_step ;
155
161
}
162
+ } else if (publish_noise_points_) {
163
+ for (int i = walk_first_idx; i <= walk_last_idx; i++) {
164
+ auto noise_ptr = reinterpret_cast <PointXYZI *>(&noise_points.data [noise_points_size]);
165
+ auto input_ptr =
166
+ reinterpret_cast <const PointXYZI *>(&input->data [indices[walk_first_idx]]);
167
+ if (transform_info.need_transform ) {
168
+ Eigen::Vector4f p (input_ptr->x , input_ptr->y , input_ptr->z , 1 );
169
+ p = transform_info.eigen_transform * p;
170
+ noise_ptr->x = p[0 ];
171
+ noise_ptr->y = p[1 ];
172
+ noise_ptr->z = p[2 ];
173
+ } else {
174
+ *noise_ptr = *input_ptr;
175
+ }
176
+ const float & intensity = *reinterpret_cast <const float *>(
177
+ &input->data [indices[walk_first_idx] + intensity_offset]);
178
+ noise_ptr->intensity = intensity;
179
+
180
+ noise_points_size += noise_points.point_step ;
181
+ }
156
182
}
157
183
158
184
walk_first_idx = idx + 1 ;
@@ -182,37 +208,32 @@ void RingOutlierFilterComponent::faster_filter(
182
208
183
209
output_size += output.point_step ;
184
210
}
211
+ } else if (publish_noise_points_) {
212
+ for (int i = walk_first_idx; i < walk_last_idx; i++) {
213
+ auto noise_ptr = reinterpret_cast <PointXYZI *>(&noise_points.data [noise_points_size]);
214
+ auto input_ptr = reinterpret_cast <const PointXYZI *>(&input->data [indices[i]]);
215
+ if (transform_info.need_transform ) {
216
+ Eigen::Vector4f p (input_ptr->x , input_ptr->y , input_ptr->z , 1 );
217
+ p = transform_info.eigen_transform * p;
218
+ noise_ptr->x = p[0 ];
219
+ noise_ptr->y = p[1 ];
220
+ noise_ptr->z = p[2 ];
221
+ } else {
222
+ *noise_ptr = *input_ptr;
223
+ }
224
+ const float & intensity =
225
+ *reinterpret_cast <const float *>(&input->data [indices[i] + intensity_offset]);
226
+ noise_ptr->intensity = intensity;
227
+ noise_points_size += noise_points.point_step ;
228
+ }
185
229
}
186
230
}
187
231
188
- output. data . resize ( output_size);
232
+ setUpPointCloudFormat (input, output, output_size, /* num_fields= */ 4 );
189
233
190
- // Note that `input->header.frame_id` is data before converted when `transform_info.need_transform
191
- // == true`
192
- output.header .frame_id = !tf_input_frame_.empty () ? tf_input_frame_ : tf_input_orig_frame_;
193
-
194
- output.height = 1 ;
195
- output.width = static_cast <uint32_t >(output.data .size () / output.height / output.point_step );
196
- output.is_bigendian = input->is_bigendian ;
197
- output.is_dense = input->is_dense ;
198
-
199
- // set fields
200
- sensor_msgs::PointCloud2Modifier pcd_modifier (output);
201
- constexpr int num_fields = 4 ;
202
- pcd_modifier.setPointCloud2Fields (
203
- num_fields, " x" , 1 , sensor_msgs::msg::PointField::FLOAT32, " y" , 1 ,
204
- sensor_msgs::msg::PointField::FLOAT32, " z" , 1 , sensor_msgs::msg::PointField::FLOAT32,
205
- " intensity" , 1 , sensor_msgs::msg::PointField::FLOAT32);
206
-
207
- if (publish_excluded_points_) {
208
- auto excluded_points = extractExcludedPoints (*input, output, 0.01 );
209
- // set fields
210
- sensor_msgs::PointCloud2Modifier excluded_pcd_modifier (excluded_points);
211
- excluded_pcd_modifier.setPointCloud2Fields (
212
- num_fields, " x" , 1 , sensor_msgs::msg::PointField::FLOAT32, " y" , 1 ,
213
- sensor_msgs::msg::PointField::FLOAT32, " z" , 1 , sensor_msgs::msg::PointField::FLOAT32,
214
- " intensity" , 1 , sensor_msgs::msg::PointField::FLOAT32);
215
- excluded_points_publisher_->publish (excluded_points);
234
+ if (publish_noise_points_) {
235
+ setUpPointCloudFormat (input, noise_points, noise_points_size, /* num_fields=*/ 4 );
236
+ noise_points_publisher_->publish (noise_points);
216
237
}
217
238
218
239
// add processing time for debug
@@ -260,9 +281,8 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba
260
281
if (get_param (p, " num_points_threshold" , num_points_threshold_)) {
261
282
RCLCPP_DEBUG (get_logger (), " Setting new num_points_threshold to: %d." , num_points_threshold_);
262
283
}
263
- if (get_param (p, " publish_excluded_points" , publish_excluded_points_)) {
264
- RCLCPP_DEBUG (
265
- get_logger (), " Setting new publish_excluded_points to: %d." , publish_excluded_points_);
284
+ if (get_param (p, " publish_noise_points" , publish_noise_points_)) {
285
+ RCLCPP_DEBUG (get_logger (), " Setting new publish_noise_points to: %d." , publish_noise_points_);
266
286
}
267
287
268
288
rcl_interfaces::msg::SetParametersResult result;
@@ -272,51 +292,27 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba
272
292
return result;
273
293
}
274
294
275
- sensor_msgs::msg::PointCloud2 RingOutlierFilterComponent::extractExcludedPoints (
276
- const sensor_msgs::msg::PointCloud2 & input, const sensor_msgs::msg:: PointCloud2 & output ,
277
- float epsilon )
295
+ void RingOutlierFilterComponent::setUpPointCloudFormat (
296
+ const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size ,
297
+ size_t num_fields )
278
298
{
279
- // Convert ROS PointCloud2 message to PCL point cloud for easier manipulation
280
- pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
281
- pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZ>);
282
- pcl::fromROSMsg (input, *input_cloud);
283
- pcl::fromROSMsg (output, *output_cloud);
284
-
285
- pcl::PointCloud<pcl::PointXYZ>::Ptr excluded_points (new pcl::PointCloud<pcl::PointXYZ>);
286
-
287
- pcl::search::Search<pcl::PointXYZ>::Ptr tree;
288
- if (output_cloud->isOrganized ()) {
289
- tree.reset (new pcl::search::OrganizedNeighbor<pcl::PointXYZ>());
290
- } else {
291
- tree.reset (new pcl::search::KdTree<pcl::PointXYZ>(false ));
292
- }
293
- tree->setInputCloud (output_cloud);
294
- std::vector<int > nn_indices (1 );
295
- std::vector<float > nn_distances (1 );
296
- for (const auto & point : input_cloud->points ) {
297
- if (!tree->nearestKSearch (point, 1 , nn_indices, nn_distances)) {
298
- continue ;
299
- }
300
- if (nn_distances[0 ] > epsilon) {
301
- excluded_points->points .push_back (point);
302
- }
303
- }
304
-
305
- sensor_msgs::msg::PointCloud2 excluded_points_msg;
306
- pcl::toROSMsg (*excluded_points, excluded_points_msg);
307
-
308
- // Set the metadata for the excluded points message based on the input cloud
309
- excluded_points_msg.height = 1 ;
310
- excluded_points_msg.width =
311
- static_cast <uint32_t >(output.data .size () / output.height / output.point_step );
312
- excluded_points_msg.row_step = static_cast <uint32_t >(output.data .size () / output.height );
313
- excluded_points_msg.is_bigendian = input.is_bigendian ;
314
- excluded_points_msg.is_dense = input.is_dense ;
315
- excluded_points_msg.header = input.header ;
316
- excluded_points_msg.header .frame_id =
299
+ formatted_points.data .resize (points_size);
300
+ // Note that `input->header.frame_id` is data before converted when `transform_info.need_transform
301
+ // == true`
302
+ formatted_points.header .frame_id =
317
303
!tf_input_frame_.empty () ? tf_input_frame_ : tf_input_orig_frame_;
318
-
319
- return excluded_points_msg;
304
+ formatted_points.data .resize (formatted_points.point_step * input->width );
305
+ formatted_points.height = 1 ;
306
+ formatted_points.width =
307
+ static_cast <uint32_t >(formatted_points.data .size () / formatted_points.point_step );
308
+ formatted_points.is_bigendian = input->is_bigendian ;
309
+ formatted_points.is_dense = input->is_dense ;
310
+
311
+ sensor_msgs::PointCloud2Modifier pcd_modifier (formatted_points);
312
+ pcd_modifier.setPointCloud2Fields (
313
+ num_fields, " x" , 1 , sensor_msgs::msg::PointField::FLOAT32, " y" , 1 ,
314
+ sensor_msgs::msg::PointField::FLOAT32, " z" , 1 , sensor_msgs::msg::PointField::FLOAT32,
315
+ " intensity" , 1 , sensor_msgs::msg::PointField::FLOAT32);
320
316
}
321
317
322
318
} // namespace pointcloud_preprocessor
0 commit comments