From b10dc10a903f8e82f5bfaed294692be822754a2d Mon Sep 17 00:00:00 2001 From: Shinnosuke Hirakawa <8327162+0x126@users.noreply.github.com> Date: Fri, 25 Feb 2022 16:21:37 +0900 Subject: [PATCH] fix: change empty pointcloud processing (#444) Signed-off-by: Shinnosuke Hirakawa --- .../src/concatenate_data/concatenate_data_nodelet.cpp | 4 ---- .../outlier_filter/dual_return_outlier_filter_nodelet.cpp | 5 ----- .../src/outlier_filter/ring_outlier_filter_nodelet.cpp | 4 ---- 3 files changed, 13 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp index 60eacb9b09ba7..8808cf3db0d83 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp @@ -354,10 +354,6 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name) { std::lock_guard lock(mutex_); - if (input_ptr->data.empty()) { - RCLCPP_WARN(get_logger(), "input pointcloud is empty."); - return; - } sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2()); convertToXYZICloud(input_ptr, xyzi_input_ptr); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index d506031d12d22..7858322713063 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -87,11 +87,6 @@ void DualReturnOutlierFilterComponent::filter( PointCloud2 & output) { boost::mutex::scoped_lock lock(mutex_); - if (input->data.empty()) { - output.header = input->header; - RCLCPP_WARN(get_logger(), "input pointcloud is empty."); - return; - } pcl::PointCloud::Ptr pcl_input( new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index 5667accdfdbf0..7a842665e5f14 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -39,10 +39,6 @@ void RingOutlierFilterComponent::filter( PointCloud2 & output) { boost::mutex::scoped_lock lock(mutex_); - output.header = input->header; - if (input->row_step < 1) { - return; - } std::unordered_map> input_ring_map; input_ring_map.reserve(128); sensor_msgs::msg::PointCloud2::SharedPtr input_ptr =