14 #include <gtest/gtest.h> 17 #include "../../include/ecl/geometry/cartesian_point.hpp" 18 #include "../../include/ecl/geometry/pascals_triangle.hpp" 19 #include "../../include/ecl/geometry/polynomial.hpp" 42 TEST(PolynomialTests,pascalsTriangle) {
50 EXPECT_EQ(2,*(iter3+5));
60 EXPECT_EQ(3,*(iter5+8));
69 EXPECT_EQ(4,*(iter4+8));
72 TEST(PolynomialTests,quadratic) {
80 EXPECT_GT(33.40,p(5.3)); EXPECT_LT(33.38,p(5.3));
83 EXPECT_GT(14.20,p(5.3)); EXPECT_LT(14.18,p(5.3));
86 TEST(PolynomialTests,cubic) {
88 p.coefficients() << 3, 1, 1, 1;
90 double maximum = ecl::CubicPolynomial::Maximum(0.0, 0.2, p);
93 EXPECT_DOUBLE_EQ(maximum, 3.248);
96 TEST(PolynomialTests,linear_function) {
98 f = LinearFunction::PointSlopeForm(1.0,3.0,2.0);
99 g = LinearFunction::PointSlopeForm(0.0,4.0,-1.0);
101 EXPECT_DOUBLE_EQ(point.x(),1.0);
102 EXPECT_DOUBLE_EQ(point.y(),3.0);
107 point = intersection(f,f);
112 EXPECT_EQ(caught,
true);
113 EXPECT_EQ(intersection.fail(),
true);
119 roots = LinearFunction::Roots(f);
120 EXPECT_EQ(1,roots.
size());
121 if ( roots.
size() > 0 ) {
122 EXPECT_DOUBLE_EQ(-0.5,roots[0]);
125 q.coefficients() << 1.0, 2.0, 1.0;
126 roots = QuadraticPolynomial::Roots(q);
127 EXPECT_EQ(1,roots.
size());
128 if ( roots.
size() > 0 ) {
129 EXPECT_DOUBLE_EQ(-1.0,roots[0]);
131 q.coefficients() << 2.0, 2.0, 1.0;
132 roots = QuadraticPolynomial::Roots(q);
133 EXPECT_EQ(0,roots.
size());
134 q.coefficients() << -2.0, 1.0, 1.0;
135 roots = QuadraticPolynomial::Roots(q);
136 EXPECT_EQ(2,roots.
size());
137 EXPECT_DOUBLE_EQ(1,roots[0]);
138 EXPECT_DOUBLE_EQ(-2,roots[1]);
140 c.coefficients() << -6.0, 1.0, 4.0, 1.0;
141 roots = CubicPolynomial::Roots(c);
142 EXPECT_EQ(3,roots.
size());
143 if ( roots.
size() == 3 ) {
144 EXPECT_DOUBLE_EQ(1,roots[0]);
145 EXPECT_DOUBLE_EQ(-2,roots[1]);
146 EXPECT_DOUBLE_EQ(-3,roots[2]);
148 c.coefficients() << 0, 0, 0, 1.0;
149 roots = CubicPolynomial::Roots(c);
150 EXPECT_EQ(1,roots.
size());
151 if ( roots.
size() == 1 ) {
152 EXPECT_DOUBLE_EQ(0,roots[0]);
154 c.coefficients() << -1.0, 1.0, -1.0, 1.0;
155 roots = CubicPolynomial::Roots(c);
156 EXPECT_EQ(1,roots.
size());
157 if ( roots.
size() == 1 ) {
158 EXPECT_DOUBLE_EQ(1,roots[0]);
161 TEST(PolynomialTests,division) {
163 c.coefficients() << -6.0, 1.0, 4.0, 1.0;
167 EXPECT_DOUBLE_EQ(6.0, q.coefficients()[0]);
168 EXPECT_DOUBLE_EQ(5.0, q.coefficients()[1]);
169 EXPECT_DOUBLE_EQ(1.0, q.coefficients()[2]);
170 EXPECT_DOUBLE_EQ(0.0, remainder);
172 EXPECT_DOUBLE_EQ(3.0, f.coefficients()[0]);
173 EXPECT_DOUBLE_EQ(1.0, f.coefficients()[1]);
174 EXPECT_DOUBLE_EQ(0.0, remainder);
181 int main(
int argc,
char **argv) {
185 Format<string> string_format; string_format.width(8); string_format.align(RightAlign);
186 Format<double> format; format.width(8); format.precision(2); format.align(RightAlign);
188 std::cout << std::endl;
189 std::cout <<
"***********************************************************" << std::endl;
190 std::cout <<
" Polynomial Blueprints" << std::endl;
191 std::cout <<
"***********************************************************" << std::endl;
192 std::cout << std::endl;
195 linear_function = LinearFunction::Interpolation(0.0,1.0,1.0,2.0);
196 std::cout <<
"Linear function [interpolation]: " << linear_function << std::endl;
198 linear_function = LinearFunction::PointSlopeForm(1.0,3.0,2.0);
199 std::cout <<
"Linear function [point-slope]: " << linear_function << std::endl;
202 cubic = CubicPolynomial::SecondDerivativeInterpolation(1.0,0.0,0.0,2.0,1.0,1.0);
203 std::cout << cubic << std::endl;
204 cubic = CubicPolynomial::DerivativeInterpolation(2.0,0.0,0.0,3.0,1.0,0.0);
205 std::cout << cubic << std::endl;
207 quintic = QuinticPolynomial::Interpolation(2.0,0.0,0.0,0.0,
209 std::cout << quintic << std::endl;
210 std::cout << std::endl;
212 std::cout <<
"Results" << std::endl;
213 std::cout << string_format(
"cubic");
214 std::cout << string_format(
"quintic") << std::endl;
215 for (
int i = 0; i <= 20; ++i ) {
216 std::cout << format(cubic(2.0 + 0.05*i));
217 std::cout << format(quintic(0.0 + 0.05*i)) << std::endl;
221 std::cout << std::endl;
222 std::cout <<
"***********************************************************" << std::endl;
223 std::cout <<
" Polynomial Derivatives" << std::endl;
224 std::cout <<
"***********************************************************" << std::endl;
225 std::cout << std::endl;
230 std::cout <<
"1st Derivative: " << cubic_derivative << std::endl;
231 std::cout <<
"2nd Derivative: " << cubic_dderivative << std::endl;
233 testing::InitGoogleTest(&argc,argv);
234 return RUN_ALL_TESTS();
Blueprint for interpolating a cubic polynomial between end point conditions.
CartesianPoint< double, 2 > CartesianPoint2d
Eigen style convenience handle for x, y, z triples in double format.
Specialises the function math loader for cubics.
Blueprint for interpolating a linear function connecting end point conditions.
Primary template functor for polynomial division.
Polynomial< 1 > LinearFunction
Mathematical term for 1st order polynomials.
Primary template functor for the intersection of like functions.
Polynomial< 2 > QuadraticPolynomial
Mathematical term for 2nd order polynomials.
Coefficients & coefficients()
Handle to the coefficient array, use to initialise the polynomial.
void shift_horizontal(const double &shift)
Horizontal shift transform.
int main(int argc, char **argv)
const_iterator begin(unsigned int index=0) const
Iterator generator for diagonals of pascals triangle [begin].
TEST(PolynomialTests, pascalsTriangle)
Holds the coefficients for pascal's triangle up to row N.
void f(int i) ecl_debug_throw_decl(StandardException)
Polynomial< 3 > CubicPolynomial
Mathematical term for 3rd order polynomials.
Representation of a polynomial function of n-th degree.
Polynomial< 5 > QuinticPolynomial
Mathematical term for 5th order polynomials.
Polynomial< N-1 > derivative() const
Generates the derivative polynomial.