normal_estimation_worker.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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   // Create the normal estimation class, and pass the input dataset to it
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   // Create an empty kdtree representation, and pass it to the normal estimation object.
00118   // Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).
00119   pcl::search::KdTree<pcl::PointSurfel>::Ptr tree (new pcl::search::KdTree<pcl::PointSurfel> ());
00120   normal_estimator.setSearchMethod (tree);
00121 
00122   // Use all neighbors in a sphere of the search radius
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 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:53