vtk_mesh_smoothing_windowed_sinc.h
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) 2011, 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  * $Id: vtk_mesh_smoothing_windowed_sinc.h 5066 2012-03-14 06:42:21Z rusu $
00036  *
00037  */
00038 
00039 #ifndef VTK_MESH_SMOOTHING_WINDOWED_SINC_H_
00040 #define VTK_MESH_SMOOTHING_WINDOWED_SINC_H_
00041 
00042 #include <pcl/surface/processing.h>
00043 #include <pcl/surface/vtk_smoothing/vtk.h>
00044 
00045 namespace pcl
00046 {
00052   class PCL_EXPORTS MeshSmoothingWindowedSincVTK : public MeshProcessing
00053   {
00054     public:
00056       MeshSmoothingWindowedSincVTK ()
00057         : MeshProcessing (),
00058           num_iter_ (20),
00059           pass_band_ (0.1f),
00060           feature_edge_smoothing_ (false),
00061           feature_angle_ (45.f),
00062           edge_angle_ (15.f),
00063           boundary_smoothing_ (true),
00064           normalize_coordinates_ (false)
00065       {};
00066 
00070       inline void
00071       setNumIter (int num_iter)
00072       {
00073         num_iter_ = num_iter;
00074       };
00075 
00077       inline int
00078       getNumIter ()
00079       {
00080         return num_iter_;
00081       };
00082 
00086       inline void
00087       setPassBand (float pass_band)
00088       {
00089         pass_band_ = pass_band;
00090       };
00091 
00093       inline float
00094       getPassBand ()
00095       {
00096         return pass_band_;
00097       };
00098 
00105       inline void
00106       setNormalizeCoordinates (bool normalize_coordinates)
00107       {
00108         normalize_coordinates_ = normalize_coordinates;
00109       }
00110 
00112       inline bool
00113       getNormalizeCoordinates ()
00114       {
00115         return normalize_coordinates_;
00116       }
00117 
00121       inline void
00122       setFeatureEdgeSmoothing (bool feature_edge_smoothing)
00123       {
00124         feature_edge_smoothing_ = feature_edge_smoothing;
00125       };
00126 
00128       inline bool
00129       getFeatureEdgeSmoothing ()
00130       {
00131         return feature_edge_smoothing_;
00132       };
00133 
00137       inline void
00138       setFeatureAngle (float feature_angle)
00139       {
00140         feature_angle_ = feature_angle;
00141       };
00142 
00144       inline float
00145       getFeatureAngle ()
00146       {
00147         return feature_angle_;
00148       };
00149 
00153       inline void
00154       setEdgeAngle (float edge_angle)
00155       {
00156         edge_angle_ = edge_angle;
00157       };
00158 
00160       inline float
00161       getEdgeAngle ()
00162       {
00163         return edge_angle_;
00164       };
00165 
00166 
00170       inline void
00171       setBoundarySmoothing (bool boundary_smoothing)
00172       {
00173         boundary_smoothing_ = boundary_smoothing;
00174       };
00175 
00177       inline bool
00178       getBoundarySmoothing ()
00179       {
00180         return boundary_smoothing_;
00181       }
00182 
00183 
00184     protected:
00185       void
00186       performProcessing (pcl::PolygonMesh &output);
00187 
00188     private:
00189       vtkSmartPointer<vtkPolyData> vtk_polygons_;
00190       int num_iter_;
00191       float pass_band_;
00192       bool feature_edge_smoothing_;
00193       float feature_angle_;
00194       float edge_angle_;
00195       bool boundary_smoothing_;
00196       bool normalize_coordinates_;
00197   };
00198 }
00199 #endif /* VTK_MESH_SMOOTHING_WINDOWED_SINC_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:11