poisson_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/poisson_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/surface/poisson.h>
00043 #include <pcl/surface/impl/poisson.hpp>
00044 
00046 pcl::modeler::PoissonReconstructionWorker::PoissonReconstructionWorker(const QList<CloudMeshItem*>& cloud_mesh_items, QWidget* parent) :
00047   AbstractWorker(cloud_mesh_items, parent),
00048   depth_(NULL), solver_divide_(NULL), iso_divide_(NULL), degree_(NULL), scale_(NULL), samples_per_node_(NULL)
00049 {
00050 
00051 }
00052 
00054 pcl::modeler::PoissonReconstructionWorker::~PoissonReconstructionWorker(void)
00055 {
00056   delete depth_;
00057   delete solver_divide_;
00058   delete iso_divide_;
00059   delete degree_;
00060   delete scale_;
00061   delete samples_per_node_;
00062 }
00063 
00065 void
00066 pcl::modeler::PoissonReconstructionWorker::setupParameters()
00067 {
00068   pcl::Poisson<pcl::PointSurfel> poisson;
00069   depth_ = new IntParameter("Maximum Tree Depth",
00070     "Maximum depth of the tree that will be used for surface reconstruction. \
00071     Running at depth d corresponds to solving on a voxel grid whose resolution \
00072     is no larger than 2^d x 2^d x 2^d. Note that since the reconstructor adapts \
00073     the octree to the sampling density, the specified reconstruction depth \
00074     is only an upper bound.",
00075     poisson.getDepth(), 2, 16);
00076 
00077   solver_divide_ = new IntParameter("Solver Divide",
00078     "The depth at which a block Gauss-Seidel solver is used to solve the Laplacian \
00079     equation. Using this parameter helps reduce the memory overhead at the cost of \
00080     a small increase in reconstruction time. (In practice, we have found that for \
00081     reconstructions of depth 9 or higher a subdivide depth of 7 or 8 can greatly \
00082     reduce the memory usage.)",
00083     poisson.getSolverDivide(), 2, 16);
00084 
00085   iso_divide_ = new IntParameter("Iso Divide",
00086     "Depth at which a block iso-surface extractor should be used to extract the \
00087     iso-surface. Using this parameter helps reduce the memory overhead at the cost \
00088     of a small increase in extraction time. (In practice, we have found that for \
00089     reconstructions of depth 9 or higher a subdivide depth of 7 or 8 can greatly \
00090     reduce the memory usage.)",
00091     poisson.getIsoDivide(), 2, 16);
00092 
00093   degree_ = new IntParameter("Degree", "Degree", poisson.getDegree(), 1, 5);
00094 
00095   scale_ = new DoubleParameter("Scale",
00096     "The ratio between the diameter of the cube used for reconstruction and the \
00097     diameter of the samples' bounding cube.",
00098     poisson.getScale(), 0.1, 10.0, 0.01);
00099 
00100   samples_per_node_ = new DoubleParameter("Samples Per Node",
00101     "The minimum number of sample points that should fall within an octree node as \
00102     the octree construction is adapted to sampling density. For noise-free samples, small \
00103     values in the range [1.0 - 5.0] can be used. For more noisy samples, larger values in \
00104     the range [15.0 - 20.0] may be needed to provide a smoother, noise-reduced, reconstruction.",
00105     poisson.getScale(), 0.1, 10.0, 0.01);
00106 
00107   parameter_dialog_->addParameter(depth_);
00108   parameter_dialog_->addParameter(solver_divide_);
00109   parameter_dialog_->addParameter(iso_divide_);
00110   parameter_dialog_->addParameter(degree_);
00111   parameter_dialog_->addParameter(scale_);
00112   parameter_dialog_->addParameter(samples_per_node_);
00113 
00114   return;
00115 }
00116 
00118 void
00119 pcl::modeler::PoissonReconstructionWorker::processImpl(CloudMeshItem* cloud_mesh_item)
00120 {
00121   pcl::Poisson<pcl::PointSurfel> poisson;
00122   poisson.setDegree(*depth_);
00123   poisson.setSolverDivide(*solver_divide_);
00124   poisson.setIsoDivide(*iso_divide_);
00125   poisson.setDegree(*degree_);
00126   poisson.setScale (float (*scale_));
00127   poisson.setScale (float (*samples_per_node_));
00128 
00129   poisson.setConfidence(true);
00130   poisson.setManifold(true);
00131 
00132   poisson.setInputCloud(cloud_mesh_item->getCloudMesh()->getCloud());
00133 
00134   CloudMesh::PointCloudPtr cloud(new CloudMesh::PointCloud());
00135   poisson.reconstruct(*cloud, cloud_mesh_item->getCloudMesh()->getPolygons());
00136   cloud_mesh_item->getCloudMesh()->getCloud() = cloud;
00137 
00138   return;
00139 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:11