Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <pcl/apps/modeler/voxel_grid_downsample_worker.h>
00038 #include <pcl/apps/modeler/parameter.h>
00039 #include <pcl/apps/modeler/parameter_dialog.h>
00040 #include <pcl/apps/modeler/cloud_mesh.h>
00041 #include <pcl/apps/modeler/cloud_mesh_item.h>
00042 #include <pcl/filters/voxel_grid.h>
00043 #include <pcl/common/common.h>
00044
00045
00047 pcl::modeler::VoxelGridDownampleWorker::VoxelGridDownampleWorker(const QList<CloudMeshItem*>& cloud_mesh_items, QWidget* parent) :
00048 AbstractWorker(cloud_mesh_items, parent),
00049 x_min_(std::numeric_limits<double>::max()), x_max_(std::numeric_limits<double>::min()),
00050 y_min_(std::numeric_limits<double>::max()), y_max_(std::numeric_limits<double>::min()),
00051 z_min_(std::numeric_limits<double>::max()), z_max_(std::numeric_limits<double>::min()),
00052 leaf_size_x_(NULL), leaf_size_y_(NULL), leaf_size_z_(NULL)
00053 {
00054 }
00055
00057 pcl::modeler::VoxelGridDownampleWorker::~VoxelGridDownampleWorker(void)
00058 {
00059 delete leaf_size_x_;
00060 delete leaf_size_y_;
00061 delete leaf_size_z_;
00062 }
00063
00065 void
00066 pcl::modeler::VoxelGridDownampleWorker::initParameters(CloudMeshItem* cloud_mesh_item)
00067 {
00068 Eigen::Vector4f min_pt, max_pt;
00069 pcl::getMinMax3D(*(cloud_mesh_item->getCloudMesh()->getCloud()), min_pt, max_pt);
00070
00071 x_min_ = std::min(double(min_pt.x()), x_min_);
00072 x_max_ = std::max(double(max_pt.x()), x_max_);
00073
00074 y_min_ = std::min(double(min_pt.y()), y_min_);
00075 y_max_ = std::max(double(max_pt.y()), y_max_);
00076
00077 z_min_ = std::min(double(min_pt.z()), z_min_);
00078 z_max_ = std::max(double(max_pt.z()), z_max_);
00079
00080 return;
00081 }
00082
00084 void
00085 pcl::modeler::VoxelGridDownampleWorker::setupParameters()
00086 {
00087 double x_range = x_max_ - x_min_;
00088 double y_range = y_max_ - y_min_;
00089 double z_range = z_max_ - z_min_;
00090
00091 double range_max = std::max(x_range, std::max(y_range, z_range));
00092 double size = range_max/1000;
00093 double step = range_max/1000;
00094
00095 leaf_size_x_ = new DoubleParameter("Leaf Size X", "The X size of the voxel grid", size, 0, x_max_-x_min_, step);
00096 leaf_size_y_ = new DoubleParameter("Leaf Size Y", "The Y size of the voxel grid", size, 0, y_max_-y_min_, step);
00097 leaf_size_z_ = new DoubleParameter("Leaf Size Z", "The Z size of the voxel grid", size, 0, z_max_-z_min_, step);
00098
00099 parameter_dialog_->addParameter(leaf_size_x_);
00100 parameter_dialog_->addParameter(leaf_size_y_);
00101 parameter_dialog_->addParameter(leaf_size_z_);
00102
00103 return;
00104 }
00105
00107 void
00108 pcl::modeler::VoxelGridDownampleWorker::processImpl(CloudMeshItem* cloud_mesh_item)
00109 {
00110 pcl::VoxelGrid<pcl::PointSurfel> voxel_grid;
00111 voxel_grid.setInputCloud(cloud_mesh_item->getCloudMesh()->getCloud());
00112 voxel_grid.setLeafSize (float (*leaf_size_x_), float (*leaf_size_y_), float (*leaf_size_z_));
00113
00114 CloudMesh::PointCloudPtr cloud(new CloudMesh::PointCloud());
00115 voxel_grid.filter(*cloud);
00116
00117 cloud_mesh_item->getCloudMesh()->getCloud() = cloud;
00118
00119 emitDataUpdated(cloud_mesh_item);
00120
00121 return;
00122 }