bivariate_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) 2010-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: bivariate_polynomial.h 5026 2012-03-12 02:51:44Z rusu $
00037  *
00038  */
00039 #ifndef BIVARIATE_POLYNOMIAL_H
00040 #define BIVARIATE_POLYNOMIAL_H
00041 
00042 #include <fstream>
00043 #include <iostream>
00044 
00045 namespace pcl 
00046 {
00051   template<typename real>
00052   class BivariatePolynomialT 
00053   {
00054     public:
00055       //-----CONSTRUCTOR&DESTRUCTOR-----
00057       BivariatePolynomialT (int new_degree=0);
00059       BivariatePolynomialT (const BivariatePolynomialT& other);
00061       ~BivariatePolynomialT ();
00062 
00063       //-----OPERATORS-----
00065       BivariatePolynomialT&
00066       operator= (const BivariatePolynomialT& other) { deepCopy (other); return *this;}
00067 
00068       //-----METHODS-----
00070       void
00071       setDegree (int new_degree);
00072 
00074       unsigned int
00075       getNoOfParameters () const { return getNoOfParametersFromDegree (degree);}
00076 
00078       real
00079       getValue (real x, real y) const;  
00080 
00083       void
00084       calculateGradient (bool forceRecalc=false);
00085 
00087       void
00088       getValueOfGradient (real x, real y, real& gradX, real& gradY);
00089 
00092       void
00093       findCriticalPoints (std::vector<real>& x_values, std::vector<real>& y_values, std::vector<int>& types) const;
00094       
00096       void
00097       writeBinary (std::ostream& os) const;
00098 
00100       void
00101       writeBinary (const char* filename) const;
00102 
00104       void
00105       readBinary (std::istream& os);
00106 
00108       void
00109       readBinary (const char* filename);
00110       
00112       static unsigned int
00113       getNoOfParametersFromDegree (int n) { return ((n+2)* (n+1))/2;}
00114 
00115       //-----VARIABLES-----
00116       int degree;
00117       real* parameters;
00118       BivariatePolynomialT<real>* gradient_x, * gradient_y;
00119       
00120     protected:
00121       //-----METHODS-----
00123       void
00124       memoryCleanUp ();
00125 
00127       void
00128       deepCopy (const BivariatePolynomialT<real>& other);
00129     //-----VARIABLES-----
00130   };
00131 
00132   template<typename real>
00133   std::ostream&
00134     operator<< (std::ostream& os, const BivariatePolynomialT<real>& p);
00135 
00136   typedef BivariatePolynomialT<double> BivariatePolynomiald;
00137   typedef BivariatePolynomialT<float>  BivariatePolynomial;
00138 
00139 }  // end namespace
00140 
00141 #include <pcl/common/impl/bivariate_polynomial.hpp>
00142 
00143 #endif


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:40