Go to the documentation of this file.00001
00012
00013
00014
00015
00016 #include <iostream>
00017
00018 #include <ecl/exceptions/standard_exception.hpp>
00019 #include <ecl/math/constants.hpp>
00020 #include <ecl/math/fuzzy.hpp>
00021 #include <ecl/math/simple.hpp>
00022 #include "../../include/ecl/geometry/polynomial.hpp"
00023
00024
00025
00026
00027
00028 namespace ecl {
00029
00030
00031
00032
00033
00034 LinearFunction Division< QuadraticPolynomial >::operator()(const QuadraticPolynomial &p, const double &factor, double &remainder) {
00035 double a, b;
00036 a = p.coefficients()[2];
00037 b = p.coefficients()[1] + factor*a;
00038 LinearFunction f;
00039 f.coefficients() << b, a;
00040 remainder = p.coefficients()[0]+factor*b;
00041 return f;
00042 }
00043
00044 QuadraticPolynomial Division< CubicPolynomial >::operator()(const CubicPolynomial &p, const double &factor, double &remainder) {
00045 double a, b, c;
00046 a = p.coefficients()[3];
00047 b = p.coefficients()[2] + factor*a;
00048 c = p.coefficients()[1] + factor*b;
00049 QuadraticPolynomial q;
00050 q.coefficients() << c, b, a;
00051 remainder = p.coefficients()[0]+factor*c;
00052 return q;
00053 }
00054
00055
00056
00057
00058
00059 Array<double> Roots< LinearFunction >::operator()(const LinearFunction& p) {
00060 Array<double> intercepts;
00061 double a = p.coefficients()[1];
00062 double b = p.coefficients()[0];
00063 if ( a != 0 ) {
00064 intercepts.resize(1);
00065 intercepts << -1.0*b/a;
00066 }
00067 return intercepts;
00068 }
00069
00070 Array<double> Roots< QuadraticPolynomial >::operator()(const QuadraticPolynomial& p) {
00071 Array<double> intercepts;
00072 double a = p.coefficients()[2];
00073 double b = p.coefficients()[1];
00074 double c = p.coefficients()[0];
00075 if ( a == 0 ) {
00076 LinearFunction f;
00077 f.coefficients() << c, b;
00078 intercepts = Roots<LinearFunction>()(f);
00079 } else {
00080 double discriminant = b*b - 4*a*c;
00081 if ( discriminant > 0.0 ) {
00082 intercepts.resize(2);
00083 intercepts << (-b + sqrt(discriminant))/(2*a), (-b - sqrt(discriminant))/(2*a);
00084 } else if ( discriminant == 0.0 ) {
00085 intercepts.resize(1);
00086 intercepts << -b/(2*a);
00087 }
00088 }
00089 return intercepts;
00090 }
00091
00092
00093 Array<double> Roots< CubicPolynomial >::operator()(const CubicPolynomial& polynomial) {
00094 Array<double> intercepts;
00095 double a = polynomial.coefficients()[3];
00096 double b = polynomial.coefficients()[2];
00097 double c = polynomial.coefficients()[1];
00098 double d = polynomial.coefficients()[0];
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108 double p = (3*a*c - b*b)/(3*a*a);
00109 double q = (2*b*b*b - 9*a*b*c + 27*a*a*d)/(27*a*a*a);
00110 double discriminant = p*p*p/27 + q*q/4;
00111
00112
00113
00114 double shift = -b/(3*a);
00115 if ( ( p == 0 ) && ( q == 0 ) ) {
00116
00117 intercepts.resize(1);
00118 intercepts << shift;
00119
00120 } else if ( p == 0 ) {
00121
00122
00123 intercepts.resize(1);
00124 intercepts << ecl::cube_root(-q)+ shift;
00125 } else if ( q == 0 ) {
00126
00127
00128 intercepts.resize(3);
00129 intercepts << shift, sqrt(-1*p) + shift, -sqrt(-1*p) + shift;
00130 } else if ( discriminant == 0 ) {
00131
00132
00133 intercepts.resize(2);
00134 intercepts << 3*q/p + shift, (-3*q)/(2*p) + shift;
00135 } else if ( discriminant >= 0 ) {
00136
00137 double u = ecl::cube_root(-q/2 + sqrt(discriminant));
00138 double v = ecl::cube_root(-q/2 - sqrt(discriminant));
00139 intercepts.resize(1);
00140 intercepts << u + v + shift;
00141 } else {
00142
00143
00144
00145 double t_1 = 2.0*sqrt(-p/3.0)*cos((1.0/3.0)*acos( ((3.0*q)/(2.0*p)) * sqrt(-3.0/p)));
00146 double t_2 = 2.0*sqrt(-p/3.0)*cos((1.0/3.0)*acos(( (3.0*q)/(2.0*p)) * sqrt(-3.0/p))-(2.0*ecl::pi)/3.0);
00147 double t_3 = 2.0*sqrt(-p/3.0)*cos((1.0/3.0)*acos(( (3.0*q)/(2.0*p)) * sqrt(-3.0/p))-(4.0*ecl::pi)/3.0);
00148 intercepts.resize(3);
00149 intercepts << t_1+shift, t_2+shift, t_3+shift;
00150 }
00151 return intercepts;
00152 }
00153
00154 CartesianPoint2d Intersection< LinearFunction >::operator()(const LinearFunction &f, const LinearFunction &g) ecl_throw_decl(StandardException) {
00155 CartesianPoint2d point;
00156 double a_0 = f.coefficients()[0];
00157 double b_0 = f.coefficients()[1];
00158 double a_1 = g.coefficients()[0];
00159 double b_1 = g.coefficients()[1];
00160 if ( isApprox(b_0, b_1) ) {
00161 last_operation_failed = true;
00162 ecl_throw(StandardException(LOC,OutOfRangeError,"Functions are collinear, no intersection possible."));
00163 } else {
00164 point.x((a_0 - a_1)/(b_1 - b_0));
00165 point.y(f(point.x()));
00166 }
00167 return point;
00168 }
00169
00170 double Maximum< LinearFunction >::operator()(
00171 const double& x_begin, const double& x_end, const LinearFunction &function) {
00172 double max = function(x_begin);
00173 double test_max = function(x_end);
00174 if ( test_max > max ) {
00175 max = test_max;
00176 }
00177 return max;
00178 }
00179
00180 double Maximum<CubicPolynomial>::operator()(
00181 const double& x_begin, const double& x_end, const CubicPolynomial& cubic) {
00182
00183 double max = cubic(x_begin);
00184 double test_max = cubic(x_end);
00185 if ( test_max > max ) {
00186 max = test_max;
00187 }
00188 CubicPolynomial::Coefficients coefficients = cubic.coefficients();
00189 double a = 3*coefficients[3];
00190 double b = 2*coefficients[2];
00191 double c = coefficients[1];
00192 if ( a == 0 ) {
00193 double root = -c/b;
00194 if ( ( root > x_begin ) && ( root < x_end ) ) {
00195 test_max = cubic(root);
00196 if ( test_max > max ) {
00197 max = test_max;
00198 }
00199 }
00200 } else {
00201 double sqrt_term = b*b-4*a*c;
00202 if ( sqrt_term > 0 ) {
00203 double root = ( -b + sqrt(b*b-4*a*c))/(2*a);
00204 if ( ( root > x_begin ) && ( root < x_end ) ) {
00205 test_max = cubic(root);
00206 if ( test_max > max ) {
00207 max = test_max;
00208 }
00209 }
00210 root = ( -b - sqrt(b*b-4*a*c))/(2*a);
00211 if ( ( root > x_begin ) && ( root < x_end ) ) {
00212 test_max = cubic(root);
00213 if ( test_max > max ) {
00214 max = test_max;
00215 }
00216 }
00217 }
00218 }
00219 return max;
00220 }
00221
00222 double Minimum< LinearFunction >::operator()(
00223 const double& x_begin, const double& x_end, const LinearFunction &function) {
00224 double min = function(x_begin);
00225 double test_min = function(x_end);
00226 if ( test_min < min ) {
00227 min = test_min;
00228 }
00229 return min;
00230 }
00231
00232 double Minimum<CubicPolynomial>::operator()(
00233 const double& x_begin, const double& x_end, const CubicPolynomial& cubic) {
00234
00235 double min = cubic(x_begin);
00236 double test_min = cubic(x_end);
00237 if ( test_min < min ) {
00238 min = test_min;
00239 }
00240 CubicPolynomial::Coefficients coefficients = cubic.coefficients();
00241 double a = 3*coefficients[3];
00242 double b = 2*coefficients[2];
00243 double c = coefficients[1];
00244 if ( a == 0 ) {
00245 double root = -c/b;
00246 if ( ( root > x_begin ) && ( root < x_end ) ) {
00247 test_min = cubic(root);
00248 if ( test_min < min ) {
00249 min = test_min;
00250 }
00251 }
00252 } else {
00253 double sqrt_term = b*b-4*a*c;
00254 if ( sqrt_term > 0 ) {
00255 double root = ( -b + sqrt(b*b-4*a*c))/(2*a);
00256 if ( ( root > x_begin ) && ( root < x_end ) ) {
00257 test_min = cubic(root);
00258 if ( test_min < min ) {
00259 min = test_min;
00260 }
00261 }
00262 root = ( -b - sqrt(b*b-4*a*c))/(2*a);
00263 if ( ( root > x_begin ) && ( root < x_end ) ) {
00264 test_min = cubic(root);
00265 if ( test_min < min ) {
00266 min = test_min;
00267 }
00268 }
00269 }
00270 }
00271 return min;
00272 }
00273
00274 }