polynomial.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: polynomial.h 5531 2012-04-08 09:14:33Z aichim $
00039  *
00040  */
00041 
00042 #ifndef PCL_POISSON_POLYNOMIAL_H_
00043 #define PCL_POISSON_POLYNOMIAL_H_
00044 
00045 #include <vector>
00046 
00047 namespace pcl {
00048   namespace poisson {
00049 
00050     template<int Degree>
00051     class Polynomial{
00052     public:
00053       double coefficients[Degree+1];
00054 
00055       Polynomial(void);
00056       template<int Degree2>
00057       Polynomial(const Polynomial<Degree2>& P);
00058       double operator() (const double& t) const;
00059       double integral (const double& tMin,const double& tMax) const;
00060 
00061       int operator == (const Polynomial& p) const;
00062       int operator != (const Polynomial& p) const;
00063       int isZero(void) const;
00064       void setZero(void);
00065 
00066       template<int Degree2>
00067       Polynomial& operator  = (const Polynomial<Degree2> &p);
00068       Polynomial& operator += (const Polynomial& p);
00069       Polynomial& operator -= (const Polynomial& p);
00070       Polynomial  operator -  (void) const;
00071       Polynomial  operator +  (const Polynomial& p) const;
00072       Polynomial  operator -  (const Polynomial& p) const;
00073       template<int Degree2>
00074       Polynomial<Degree+Degree2>  operator *  (const Polynomial<Degree2>& p) const;
00075 
00076       Polynomial& operator += (const double& s);
00077       Polynomial& operator -= (const double& s);
00078       Polynomial& operator *= (const double& s);
00079       Polynomial& operator /= (const double& s);
00080       Polynomial  operator +  (const double& s) const;
00081       Polynomial  operator -  (const double& s) const;
00082       Polynomial  operator *  (const double& s) const;
00083       Polynomial  operator /  (const double& s) const;
00084 
00085       Polynomial scale (const double& s) const;
00086       Polynomial shift (const double& t) const;
00087 
00088       Polynomial<Degree-1> derivative (void) const;
00089       Polynomial<Degree+1> integral (void) const;
00090 
00091       void printnl (void) const;
00092 
00093       Polynomial& addScaled (const Polynomial& p, const double& scale);
00094 
00095       static void Negate (const Polynomial& in, Polynomial& out);
00096       static void Subtract (const Polynomial& p1, const Polynomial& p2, Polynomial& q);
00097       static void Scale (const Polynomial& p, const double& w, Polynomial& q);
00098       static void AddScaled (const Polynomial& p1, const double& w1, const Polynomial& p2, const double& w2, Polynomial& q);
00099       static void AddScaled (const Polynomial& p1, const Polynomial& p2, const double& w2, Polynomial& q);
00100       static void AddScaled (const Polynomial& p1, const double& w1, const Polynomial& p2, Polynomial& q);
00101 
00102       void getSolutions (const double& c, std::vector<double>& roots, const double& EPS) const;
00103     };
00104 
00105 
00106   }
00107 }
00108 
00109 
00110 #include <pcl/surface/impl/poisson/polynomial.hpp>
00111 #endif /* PCL_POISSON_POLYNOMIAL_H_ */


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