void
pcl::modeler::VoxelGridDownampleWorker::processImpl(CloudMeshItem* cloud_mesh_item)
{
  pcl::VoxelGrid<pcl::PointSurfel> voxel_grid;
  voxel_grid.setInputCloud(cloud_mesh_item->getCloudMesh()->getCloud());
  voxel_grid.setLeafSize (float (*leaf_size_x_), float (*leaf_size_y_), float (*leaf_size_z_));

  CloudMesh::PointCloudPtr cloud(new CloudMesh::PointCloud());
  voxel_grid.filter(*cloud);

  cloud_mesh_item->getCloudMesh()->getCloud() = cloud;

  emitDataUpdated(cloud_mesh_item);

  return;
}
void
pcl::modeler::StatisticalOutlierRemovalWorker::processImpl(CloudMeshItem* cloud_mesh_item)
{
  pcl::StatisticalOutlierRemoval<pcl::PointSurfel> sor;
  sor.setInputCloud(cloud_mesh_item->getCloudMesh()->getCloud());
  sor.setMeanK(*mean_k_);
  sor.setStddevMulThresh(*stddev_mul_thresh_);

  CloudMesh::PointCloudPtr cloud(new CloudMesh::PointCloud());
  sor.filter(*cloud);

  cloud_mesh_item->getCloudMesh()->getCloud() = cloud;

  emitDataUpdated(cloud_mesh_item);

  return;
}