ppolynomial.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) 2009-2012, Willow Garage, Inc.
00006   *  Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho,
00007   *                      Johns Hopkins University
00008   *
00009   *  All rights reserved.
00010   *
00011   *  Redistribution and use in source and binary forms, with or without
00012   *  modification, are permitted provided that the following conditions
00013   *  are met:
00014   *
00015   *   * Redistributions of source code must retain the above copyright
00016   *     notice, this list of conditions and the following disclaimer.
00017   *   * Redistributions in binary form must reproduce the above
00018   *     copyright notice, this list of conditions and the following
00019   *     disclaimer in the documentation and/or other materials provided
00020   *     with the distribution.
00021   *   * Neither the name of Willow Garage, Inc. nor the names of its
00022   *     contributors may be used to endorse or promote products derived
00023   *     from this software without specific prior written permission.
00024   *
00025   *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00026   *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00027   *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00028   *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00029   *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00030   *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00031   *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00032   *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00033   *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00034   *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00035   *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036   *  POSSIBILITY OF SUCH DAMAGE.
00037   *
00038   * $Id: ppolynomial.h 5531 2012-04-08 09:14:33Z aichim $
00039   *
00040   */
00041 
00042 #ifndef PCL_POISSON_PPOLYNOMIAL_H_
00043 #define PCL_POISSON_PPOLYNOMIAL_H_
00044 
00045 #include <vector>
00046 #include "polynomial.h"
00047 
00048 
00049 namespace pcl
00050 {
00051   namespace poisson
00052   {
00053     template <int Degree> 
00054     class StartingPolynomial
00055     {
00056       public:
00057         Polynomial<Degree> p;
00058         double start;
00059 
00060         StartingPolynomial () : p (), start () {}
00061 
00062         template <int Degree2> StartingPolynomial<Degree+Degree2> operator* (const StartingPolynomial<Degree2>&p) const;
00063         StartingPolynomial scale (const double&s) const;
00064         StartingPolynomial shift (const double&t) const;
00065         int operator < (const StartingPolynomial &sp) const;
00066         static int Compare (const void *v1,const void *v2);
00067     };
00068 
00069     template <int Degree> 
00070     class PPolynomial
00071     {
00072       public:
00073         size_t polyCount;
00074         StartingPolynomial<Degree>*polys;
00075 
00076         PPolynomial (void);
00077         PPolynomial (const PPolynomial<Degree>&p);
00078         ~PPolynomial (void);
00079 
00080         PPolynomial& operator = (const PPolynomial&p);
00081 
00082         int size (void) const;
00083 
00084         void set (const size_t&size);
00085         // Note: this method will sort the elements in sps
00086         void set (StartingPolynomial<Degree>*sps,const int&count);
00087         void reset (const size_t&newSize);
00088 
00089 
00090         double operator() (const double &t) const;
00091         double integral (const double &tMin,const double &tMax) const;
00092         double Integral (void) const;
00093 
00094         template <int Degree2> PPolynomial<Degree>& operator = (const PPolynomial<Degree2>&p);
00095 
00096         PPolynomial operator + (const PPolynomial&p) const;
00097         PPolynomial operator - (const PPolynomial &p) const;
00098 
00099         template <int Degree2> PPolynomial<Degree+Degree2> operator * (const Polynomial<Degree2> &p) const;
00100 
00101         template <int Degree2> PPolynomial<Degree+Degree2> operator* (const PPolynomial<Degree2>&p) const;
00102 
00103 
00104         PPolynomial& operator += (const double&s);
00105         PPolynomial& operator -= (const double&s);
00106         PPolynomial& operator *= (const double&s);
00107         PPolynomial& operator /= (const double&s);
00108         PPolynomial operator +  (const double&s) const;
00109         PPolynomial operator -  (const double&s) const;
00110         PPolynomial operator*  (const double&s) const;
00111         PPolynomial operator /  (const double &s) const;
00112 
00113         PPolynomial& addScaled (const PPolynomial &poly,const double &scale);
00114 
00115         PPolynomial scale (const double &s) const;
00116         PPolynomial shift (const double &t) const;
00117 
00118         PPolynomial<Degree-1> derivative (void) const;
00119         PPolynomial<Degree+1> integral (void) const;
00120 
00121         void getSolutions (const double &c,
00122                            std::vector<double> &roots,
00123                            const double &EPS,
00124                            const double &min =- DBL_MAX,
00125                            const double &max=DBL_MAX) const;
00126 
00127         void printnl (void) const;
00128 
00129         PPolynomial<Degree+1> MovingAverage (const double &radius);
00130 
00131         static PPolynomial ConstantFunction (const double &width=0.5);
00132         static PPolynomial GaussianApproximation (const double &width=0.5);
00133         void write (FILE *fp,
00134                     const int &samples,
00135                     const double &min,
00136                     const double &max) const;
00137     };
00138 
00139 
00140   }
00141 }
00142 
00143 #include <pcl/surface/impl/poisson/ppolynomial.hpp>
00144 
00145 #endif /* PCL_POISSON_PPOLYNOMIAL_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:22