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/normal_estimation_worker.h>
00038 #include <pcl/apps/modeler/parameter_dialog.h>
00039 #include <pcl/apps/modeler/parameter.h>
00040 #include <pcl/apps/modeler/cloud_mesh.h>
00041 #include <pcl/apps/modeler/cloud_mesh_item.h>
00042 #include <pcl/filters/filter_indices.h>
00043 #include <pcl/features/normal_3d.h>
00044 #include <pcl/filters/voxel_grid.h>
00045 #include <pcl/common/common.h>
00046
00048 pcl::modeler::NormalEstimationWorker::NormalEstimationWorker(const QList<CloudMeshItem*>& cloud_mesh_items, QWidget* parent) :
00049 AbstractWorker(cloud_mesh_items, parent),
00050 x_min_(std::numeric_limits<double>::max()), x_max_(std::numeric_limits<double>::min()),
00051 y_min_(std::numeric_limits<double>::max()), y_max_(std::numeric_limits<double>::min()),
00052 z_min_(std::numeric_limits<double>::max()), z_max_(std::numeric_limits<double>::min()),
00053 search_radius_(NULL)
00054 {
00055
00056 }
00057
00059 pcl::modeler::NormalEstimationWorker::~NormalEstimationWorker(void)
00060 {
00061 delete search_radius_;
00062 }
00063
00065 void
00066 pcl::modeler::NormalEstimationWorker::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::NormalEstimationWorker::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 radius = range_max/100;
00093 double step = range_max/1000;
00094
00095 search_radius_ = new DoubleParameter("Search Radius",
00096 "The sphere radius that is to be used for determining the nearest neighbors", radius, 0, x_max_-x_min_, step);
00097
00098 parameter_dialog_->addParameter(search_radius_);
00099
00100 return;
00101 }
00102
00104 void
00105 pcl::modeler::NormalEstimationWorker::processImpl(CloudMeshItem* cloud_mesh_item)
00106 {
00107 CloudMesh::PointCloudPtr cloud = cloud_mesh_item->getCloudMesh()->getCloud();
00108
00109
00110 pcl::NormalEstimation<pcl::PointSurfel, pcl::PointNormal> normal_estimator;
00111 normal_estimator.setInputCloud(cloud);
00112
00113 pcl::IndicesPtr indices(new std::vector<int>());
00114 pcl::removeNaNFromPointCloud(*cloud, *indices);
00115 normal_estimator.setIndices(indices);
00116
00117
00118
00119 pcl::search::KdTree<pcl::PointSurfel>::Ptr tree (new pcl::search::KdTree<pcl::PointSurfel> ());
00120 normal_estimator.setSearchMethod (tree);
00121
00122
00123 normal_estimator.setRadiusSearch (*search_radius_);
00124
00125 pcl::PointCloud<pcl::PointNormal> normals;
00126 normal_estimator.compute(normals);
00127
00128 for (size_t i = 0, i_end = indices->size(); i < i_end; ++ i)
00129 {
00130 size_t dest = (*indices)[i];
00131 cloud->points[dest].normal_x = normals.points[i].normal_x;
00132 cloud->points[dest].normal_y = normals.points[i].normal_y;
00133 cloud->points[dest].normal_z = normals.points[i].normal_z;
00134 }
00135
00136 return;
00137 }