pcl::PolynomialCalculationsT< real > Class Template Reference

This provides some functionality for polynomials, like finding roots or approximating bivariate polynomials More...

#include <polynomial_calculations.h>

List of all members.

Classes

struct  Parameters
 Parameters used in this class. More...

Public Member Functions

bool bivariatePolynomialApproximation (std::vector< Eigen::Matrix< real, 3, 1 > > &samplePoints, unsigned int polynomial_degree, BivariatePolynomialT< real > &ret) const
 Same as above, using a reference for the return value.
BivariatePolynomialT< real > bivariatePolynomialApproximation (std::vector< Eigen::Matrix< real, 3, 1 > > &samplePoints, unsigned int polynomial_degree, bool &error) const
 PolynomialCalculationsT ()
void setZeroValue (real new_zero_value)
 Set the minimum value under which values are considered zero.
void solveCubicEquation (real a, real b, real c, real d, std::vector< real > &roots) const
void solveLinearEquation (real a, real b, std::vector< real > &roots) const
void solveQuadraticEquation (real a, real b, real c, std::vector< real > &roots) const
void solveQuarticEquation (real a, real b, real c, real d, real e, std::vector< real > &roots) const
 ~PolynomialCalculationsT ()

Protected Member Functions

bool isNearlyZero (real d)
 check if fabs(d)<zeroValue
bool sqrtIsNearlyZero (real d)
 check if sqrt(fabs(d))<zeroValue

Protected Attributes

Parameters parameters_

Detailed Description

template<typename real>
class pcl::PolynomialCalculationsT< real >

This provides some functionality for polynomials, like finding roots or approximating bivariate polynomials

Author:
Bastian Steder

Definition at line 16 of file polynomial_calculations.h.


Constructor & Destructor Documentation

template<typename real >
pcl::PolynomialCalculationsT< real >::PolynomialCalculationsT (  )  [inline]

Definition at line 4 of file polynomial_calculations.hpp.

template<typename real >
pcl::PolynomialCalculationsT< real >::~PolynomialCalculationsT (  )  [inline]

Definition at line 11 of file polynomial_calculations.hpp.


Member Function Documentation

template<typename real >
bool pcl::PolynomialCalculationsT< real >::bivariatePolynomialApproximation ( std::vector< Eigen::Matrix< real, 3, 1 > > &  samplePoints,
unsigned int  polynomial_degree,
pcl::BivariatePolynomialT< real > &  ret 
) const [inline]

Same as above, using a reference for the return value.

Definition at line 386 of file polynomial_calculations.hpp.

template<typename real >
pcl::BivariatePolynomialT< real > pcl::PolynomialCalculationsT< real >::bivariatePolynomialApproximation ( std::vector< Eigen::Matrix< real, 3, 1 > > &  samplePoints,
unsigned int  polynomial_degree,
bool &  error 
) const [inline]

Get the bivariate polynomial approximation for Z(X,Y) from the given sample points. The parameters a,b,c,... for the polynom are returned. The order is, e.g., for degree 1: ax+by+c and for degree 2: ax²+bxy+cx+dy²+ey+f. error is set to true if the approximation did not work for any reason (not enough points, matrix not invertible, etc.)

Definition at line 374 of file polynomial_calculations.hpp.

template<typename real>
bool pcl::PolynomialCalculationsT< real >::isNearlyZero ( real  d  )  [inline, protected]

check if fabs(d)<zeroValue

Definition at line 70 of file polynomial_calculations.h.

template<typename real>
void pcl::PolynomialCalculationsT< real >::setZeroValue ( real  new_zero_value  )  [inline]

Set the minimum value under which values are considered zero.

Definition at line 64 of file polynomial_calculations.h.

template<typename real >
void pcl::PolynomialCalculationsT< real >::solveCubicEquation ( real  a,
real  b,
real  c,
real  d,
std::vector< real > &  roots 
) const [inline]

Solves an equation of the form ax^3 + bx^2 + cx + d = 0 See http://en.wikipedia.org/wiki/Cubic_equation

Definition at line 118 of file polynomial_calculations.hpp.

template<typename real >
void pcl::PolynomialCalculationsT< real >::solveLinearEquation ( real  a,
real  b,
std::vector< real > &  roots 
) const [inline]

Solves an equation of the form ax + b = 0

Definition at line 29 of file polynomial_calculations.hpp.

template<typename real >
void pcl::PolynomialCalculationsT< real >::solveQuadraticEquation ( real  a,
real  b,
real  c,
std::vector< real > &  roots 
) const [inline]

Solves an equation of the form ax^2 + bx + c = 0 See http://en.wikipedia.org/wiki/Quadratic_equation

Definition at line 62 of file polynomial_calculations.hpp.

template<typename real >
void pcl::PolynomialCalculationsT< real >::solveQuarticEquation ( real  a,
real  b,
real  c,
real  d,
real  e,
std::vector< real > &  roots 
) const [inline]

Solves an equation of the form ax^4 + bx^3 + cx^2 +dx + e = 0 See http://en.wikipedia.org/wiki/Quartic_equation#Summary_of_Ferrari.27s_method

Definition at line 220 of file polynomial_calculations.hpp.

template<typename real>
bool pcl::PolynomialCalculationsT< real >::sqrtIsNearlyZero ( real  d  )  [inline, protected]

check if sqrt(fabs(d))<zeroValue

Definition at line 73 of file polynomial_calculations.h.


Member Data Documentation

template<typename real>
Parameters pcl::PolynomialCalculationsT< real >::parameters_ [protected]

Definition at line 76 of file polynomial_calculations.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:20 2013