polynomials.cpp
Go to the documentation of this file.
00001 
00008 /*****************************************************************************
00009 ** Includes
00010 *****************************************************************************/
00011 
00012 #include <iostream>
00013 #include <string>
00014 #include <gtest/gtest.h>
00015 #include <ecl/formatters/floats.hpp>
00016 #include <ecl/formatters/strings.hpp>
00017 #include "../../include/ecl/geometry/cartesian_point.hpp"
00018 #include "../../include/ecl/geometry/pascals_triangle.hpp"
00019 #include "../../include/ecl/geometry/polynomial.hpp"
00020 
00021 /*****************************************************************************
00022 ** Using
00023 *****************************************************************************/
00024 
00025 using std::string;
00026 using ecl::CartesianPoint2d;
00027 using ecl::RightAlign;
00028 using ecl::Format;
00029 using ecl::Division;
00030 using ecl::Intersection;
00031 using ecl::LinearFunction;
00032 using ecl::QuadraticPolynomial;
00033 using ecl::CubicPolynomial;
00034 using ecl::PascalsTriangle;
00035 using ecl::Polynomial;
00036 using ecl::QuinticPolynomial;
00037 
00038 /*****************************************************************************
00039 ** Tests
00040 *****************************************************************************/
00041 
00042 TEST(PolynomialTests,pascalsTriangle) {
00043 
00044 //    1  1  1  1
00045 //    1  2  3
00046 //    1  3
00047 //    1
00048     PascalsTriangle<3> pascals_triangle_three;
00049     PascalsTriangle<3>::const_iterator iter3 = pascals_triangle_three.begin();
00050     EXPECT_EQ(2,*(iter3+5));
00051 
00052 //    1   1   1   1   1   1
00053 //    1   2   3   4   5
00054 //    1   3   6   10
00055 //    1   4   10
00056 //    1   5
00057 //    1
00058     PascalsTriangle<5> pascals_triangle;
00059     PascalsTriangle<5>::const_iterator iter5 = pascals_triangle.begin();
00060     EXPECT_EQ(3,*(iter5+8));
00061 
00062 //    1  1  1  1  1
00063 //    1  2  3  4
00064 //    1  3  6
00065 //    1  4
00066 //    1
00067     PascalsTriangle<4> pascals_triangle_four;
00068     PascalsTriangle<4>::const_iterator iter4 = pascals_triangle_four.begin();
00069     EXPECT_EQ(4,*(iter4+8));
00070 }
00071 
00072 TEST(PolynomialTests,quadratic) {
00073     Polynomial<2> p;
00074     p.coefficients() << 0, 1, 1;
00075     EXPECT_EQ(0,p.coefficients()[0]);
00076     EXPECT_EQ(1,p.coefficients()[1]);
00077     EXPECT_EQ(1,p.coefficients()[2]);
00078 //    std::cout << "p(5.3) = " << p(5.3) << std::endl;
00079     // Allow some roundoff error here
00080     EXPECT_GT(33.40,p(5.3)); EXPECT_LT(33.38,p(5.3));
00081     p.shift_horizontal(2);
00082 //    std::cout << "p(x-2)(5.3) = " << p(5.3) << std::endl;
00083     EXPECT_GT(14.20,p(5.3)); EXPECT_LT(14.18,p(5.3));
00084 }
00085 
00086 TEST(PolynomialTests,cubic) {
00087     CubicPolynomial p;
00088     p.coefficients() << 3, 1, 1, 1;
00089 //    double maximum = ecl::Maximum<CubicPolynomial>()(0.0, 0.2, p);
00090     double maximum = ecl::CubicPolynomial::Maximum(0.0, 0.2, p);
00091     //std::cout << p << std::endl;
00092     //std::cout << "Maximum [0.0, 0.2]: " << maximum << std::endl;
00093     EXPECT_DOUBLE_EQ(maximum, 3.248);
00094 }
00095 
00096 TEST(PolynomialTests,linear_function) {
00097         LinearFunction f, g;
00098         f = LinearFunction::PointSlopeForm(1.0,3.0,2.0);
00099         g = LinearFunction::PointSlopeForm(0.0,4.0,-1.0);
00100         CartesianPoint2d point = LinearFunction::Intersection(f,g);
00101     EXPECT_DOUBLE_EQ(point.x(),1.0);
00102     EXPECT_DOUBLE_EQ(point.y(),3.0);
00103         //std::cout << "Intersection: " << point << std::endl;
00104     bool caught = false;
00105     Intersection<LinearFunction> intersection;
00106     try {
00107         point = intersection(f,f);
00108     } catch ( ecl::StandardException &e ) {
00109         // collinear
00110         caught = true;
00111     }
00112     EXPECT_EQ(caught, true);
00113     EXPECT_EQ(intersection.fail(),true);
00114 }
00115 
00116 TEST(PolynomialTests,roots) {
00117         ecl::Array<double> roots;
00118         LinearFunction f = LinearFunction::PointSlopeForm(1.0,3.0,2.0);
00119         roots = LinearFunction::Roots(f);
00120         EXPECT_EQ(1,roots.size());
00121         if ( roots.size() > 0 ) {
00122                 EXPECT_DOUBLE_EQ(-0.5,roots[0]);
00123         }
00124         QuadraticPolynomial q;
00125         q.coefficients() << 1.0, 2.0, 1.0; // x^2 + 2x + 1 (single root)
00126         roots = QuadraticPolynomial::Roots(q);
00127         EXPECT_EQ(1,roots.size());
00128         if ( roots.size() > 0 ) {
00129                 EXPECT_DOUBLE_EQ(-1.0,roots[0]);
00130         }
00131         q.coefficients() << 2.0, 2.0, 1.0; // x^2 + 2x + 2 (no roots)
00132         roots = QuadraticPolynomial::Roots(q);
00133         EXPECT_EQ(0,roots.size());
00134         q.coefficients() << -2.0, 1.0, 1.0; // x^2 + x -2 (two roots)
00135         roots = QuadraticPolynomial::Roots(q);
00136         EXPECT_EQ(2,roots.size());
00137         EXPECT_DOUBLE_EQ(1,roots[0]);
00138         EXPECT_DOUBLE_EQ(-2,roots[1]);
00139         CubicPolynomial c;
00140         c.coefficients() << -6.0, 1.0, 4.0, 1.0; // x^3 + 4x^2 + x - 6 = (x-1)(x+2)(x+3) three roots
00141         roots = CubicPolynomial::Roots(c);
00142         EXPECT_EQ(3,roots.size());
00143         if ( roots.size() == 3 ) {
00144                 EXPECT_DOUBLE_EQ(1,roots[0]);
00145                 EXPECT_DOUBLE_EQ(-2,roots[1]);
00146                 EXPECT_DOUBLE_EQ(-3,roots[2]);
00147         }
00148         c.coefficients() << 0, 0, 0, 1.0; // x^3 one triple root
00149         roots = CubicPolynomial::Roots(c);
00150         EXPECT_EQ(1,roots.size());
00151         if ( roots.size() == 1 ) {
00152                 EXPECT_DOUBLE_EQ(0,roots[0]);
00153         }
00154         c.coefficients() << -1.0, 1.0, -1.0, 1.0; // (x-1)^3  shifted by one (one real, two complex)
00155         roots = CubicPolynomial::Roots(c);
00156         EXPECT_EQ(1,roots.size());
00157         if ( roots.size() == 1 ) {
00158                 EXPECT_DOUBLE_EQ(1,roots[0]);
00159         }
00160 }
00161 TEST(PolynomialTests,division) {
00162         CubicPolynomial c;
00163         c.coefficients() << -6.0, 1.0, 4.0, 1.0; // x^3 + 4x^2 + x - 6 = (x-1)(x+2)(x+3) three roots
00164         ecl::FunctionMath<CubicPolynomial> math;
00165         double remainder;
00166         QuadraticPolynomial q = CubicPolynomial::Division(c, 1, remainder); // x^2 + 5x + 6
00167         EXPECT_DOUBLE_EQ(6.0, q.coefficients()[0]);
00168         EXPECT_DOUBLE_EQ(5.0, q.coefficients()[1]);
00169         EXPECT_DOUBLE_EQ(1.0, q.coefficients()[2]);
00170         EXPECT_DOUBLE_EQ(0.0, remainder);
00171         LinearFunction f = QuadraticPolynomial::Division(q, -2, remainder);
00172         EXPECT_DOUBLE_EQ(3.0, f.coefficients()[0]); // x + 3
00173         EXPECT_DOUBLE_EQ(1.0, f.coefficients()[1]);
00174         EXPECT_DOUBLE_EQ(0.0, remainder);
00175 }
00176 
00177 /*****************************************************************************
00178 ** Main program
00179 *****************************************************************************/
00180 
00181 int main(int argc, char **argv) {
00182 
00183         // Haven't got around to gtesting these yet.
00184 
00185         Format<string> string_format; string_format.width(8); string_format.align(RightAlign);
00186         Format<double> format; format.width(8); format.precision(2); format.align(RightAlign);
00187 
00188         std::cout << std::endl;
00189         std::cout << "***********************************************************" << std::endl;
00190         std::cout << "                  Polynomial Blueprints" << std::endl;
00191         std::cout << "***********************************************************" << std::endl;
00192         std::cout << std::endl;
00193 
00194         LinearFunction linear_function = ecl::blueprints::LinearInterpolation(0.0,1.0,1.0,2.0);
00195         linear_function = LinearFunction::Interpolation(0.0,1.0,1.0,2.0);
00196         std::cout << "Linear function [interpolation]: " << linear_function << std::endl;
00197         linear_function = ecl::blueprints::LinearPointSlopeForm(1.0,3.0,2.0);
00198         linear_function = LinearFunction::PointSlopeForm(1.0,3.0,2.0);
00199         std::cout << "Linear function   [point-slope]: " << linear_function << std::endl;
00200         CubicPolynomial cubic;
00201         cubic = ecl::blueprints::CubicDerivativeInterpolation(2.0,0.0,0.0,3.0,1.0,0.0);
00202         cubic = CubicPolynomial::SecondDerivativeInterpolation(1.0,0.0,0.0,2.0,1.0,1.0); // same thing
00203         std::cout << cubic << std::endl;
00204         cubic = CubicPolynomial::DerivativeInterpolation(2.0,0.0,0.0,3.0,1.0,0.0);
00205         std::cout << cubic << std::endl;
00206         QuinticPolynomial quintic;
00207         quintic = QuinticPolynomial::Interpolation(2.0,0.0,0.0,0.0,
00208                                                                                                  3.0,1.0,0.0,0.0);
00209         std::cout << quintic << std::endl;
00210         std::cout << std::endl;
00211 
00212         std::cout << "Results" << std::endl;
00213         std::cout << string_format("cubic");
00214         std::cout << string_format("quintic") << std::endl;
00215         for ( int i = 0; i <= 20; ++i ) {
00216                 std::cout << format(cubic(2.0 + 0.05*i));
00217                 std::cout << format(quintic(0.0 + 0.05*i)) << std::endl;
00218 //        std::cout << format(quintic(0.0 + 0.05*i)) << std::endl;
00219         }
00220 
00221         std::cout << std::endl;
00222         std::cout << "***********************************************************" << std::endl;
00223         std::cout << "                  Polynomial Derivatives" << std::endl;
00224         std::cout << "***********************************************************" << std::endl;
00225         std::cout << std::endl;
00226 
00227         Polynomial<2> cubic_derivative = cubic.derivative();
00228         Polynomial<1> cubic_dderivative = cubic_derivative.derivative();
00229 
00230         std::cout << "1st Derivative: " << cubic_derivative << std::endl;
00231         std::cout << "2nd Derivative: " << cubic_dderivative << std::endl;
00232 
00233     testing::InitGoogleTest(&argc,argv);
00234     return RUN_ALL_TESTS();
00235 }
00236 
00237 
00238 


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 21:17:52