Skip to content

Commit

Permalink
fix: change empty pointcloud processing (#444)
Browse files Browse the repository at this point in the history
Signed-off-by: Shinnosuke Hirakawa <shinnosuke.hirakawa@tier4.jp>
  • Loading branch information
0x126 authored Feb 25, 2022
1 parent 5f058a8 commit b10dc10
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -354,10 +354,6 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback(
const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name)
{
std::lock_guard<std::mutex> 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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<return_type_cloud::PointXYZIRADT>::Ptr pcl_input(
new pcl::PointCloud<return_type_cloud::PointXYZIRADT>);
pcl::fromROSMsg(*input, *pcl_input);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<uint16_t, std::vector<std::size_t>> input_ring_map;
input_ring_map.reserve(128);
sensor_msgs::msg::PointCloud2::SharedPtr input_ptr =
Expand Down

0 comments on commit b10dc10

Please sign in to comment.