cubic_spline_blueprints.cpp
Go to the documentation of this file.
00001 
00012 /*****************************************************************************
00013 ** Includes
00014 *****************************************************************************/
00015 
00016 #include <ecl/containers/array.hpp>
00017 #include <ecl/exceptions/standard_exception.hpp>
00018 #include "../../include/ecl/geometry/cubic_spline.hpp"
00019 
00020 /*****************************************************************************
00021 ** Namespaces
00022 *****************************************************************************/
00023 
00024 namespace ecl {
00025 namespace blueprints {
00026 
00027 /*****************************************************************************
00028 ** Using
00029 *****************************************************************************/
00030 
00031 using ecl::Array;
00032 using ecl::OutOfRangeError;
00033 using ecl::StandardException;
00034 
00035 /*****************************************************************************
00036 ** Implementation [C2CubicSpline]
00037 *****************************************************************************/
00038 /*
00039  * This algorithm can be found in page 115 of "Numerical Recipes in C"
00040  * [The art of scientific computing] by Press, Vetterling, Tuekolsky, Flannery.
00041  */
00042 C2CubicSpline::C2CubicSpline(const ecl::Array<double>& x_set, const ecl::Array<double>& y_set,
00043                                 const double ydot_0, const double ydot_f) ecl_assert_throw_decl(StandardException) :
00044                                     x_data(x_set),
00045                                     y_data(y_set)
00046 {
00047     if (x_data.size() < 2 || y_data.size() < 2)
00048     {
00049       ecl_throw(StandardException(LOC,OutOfRangeError) );
00050     }
00051     ecl_assert_throw( x_data.size() == y_data.size(), StandardException(LOC,OutOfRangeError) );
00052     unsigned int n = x_data.size();
00053     yddot_data.resize(n);
00054     Array<double> u(n);  // u is a temporary used in the algorithm
00055 
00056     // Initial boundary conditions
00057     yddot_data[0] = -0.5;
00058     u[0] = (3.0/(x_data[1]-x_data[0])) * ((y_data[1]-y_data[0])/(x_data[1]-x_data[0])-ydot_0);
00059     // Set up the tridiagonal matrix to solve for the accelerations
00060     for (unsigned int i = 1; i <= n-2; ++i){
00061         double sig = (x_data[i]-x_data[i-1]) / (x_data[i+1]-x_data[i-1]);
00062         double p = sig*yddot_data[i-1]+2.0;
00063         yddot_data[i] = (sig-1.0)/p;
00064         u[i] = (y_data[i+1]-y_data[i])/(x_data[i+1]-x_data[i]) -
00065                (y_data[i]-y_data[i-1])/(x_data[i]-x_data[i-1]);
00066         u[i] = (6.0*u[i]/(x_data[i+1]-x_data[i-1]) - sig*u[i-1])/p;
00067     }
00068     // Final boundary conditions
00069     double qn = 0.5;
00070     u[n-1] = (3.0/(x_data[n-1]-x_data[n-2])) * (ydot_f - (y_data[n-1]-y_data[n-2])/(x_data[n-1]-x_data[n-2]));
00071 
00072     // Back substitution loop of the tridiagonal algorithm
00073     yddot_data[n-1] = ( u[n-1] - qn*u[n-2]) / ( qn*yddot_data[n-2] + 1.0 );
00074     for ( int k = n-2; k >= 0; --k ) {
00075         yddot_data[k] = yddot_data[k]*yddot_data[k+1] + u[k];
00076     }
00077 }
00078 
00079 /*
00080  * This is a special case of the above. You'll note that only initial and
00081  * boundary conditions change here.
00082  */
00083 C2CubicSpline::C2CubicSpline(const ecl::Array<double>& x_set, const ecl::Array<double>& y_set) ecl_assert_throw_decl(StandardException) :
00084                                     x_data(x_set),
00085                                     y_data(y_set)
00086 {
00087     if (x_data.size() < 2 || y_data.size() < 2)
00088     {
00089       ecl_throw(StandardException(LOC,OutOfRangeError) );
00090     }
00091     ecl_assert_throw( x_data.size() == y_data.size(), StandardException(LOC,OutOfRangeError) );
00092     unsigned int n = x_data.size();
00093     yddot_data.resize(n);
00094     Array<double> u(n);  // u is a temporary used in the algorithm
00095 
00096     // Initial boundary conditions
00097     yddot_data[0] = 0.0;
00098     u[0] = 0.0;
00099     // Set up the tridiagonal matrix to solve for the accelerations
00100     for (unsigned int i = 1; i <= n-2; ++i){
00101         double sig = (x_data[i]-x_data[i-1]) / (x_data[i+1]-x_data[i-1]);
00102         double p = sig*yddot_data[i-1]+2.0;
00103         yddot_data[i] = (sig-1.0)/p;
00104         u[i] = (y_data[i+1]-y_data[i])/(x_data[i+1]-x_data[i]) -
00105                (y_data[i]-y_data[i-1])/(x_data[i]-x_data[i-1]);
00106         u[i] = (6.0*u[i]/(x_data[i+1]-x_data[i-1]) - sig*u[i-1])/p;
00107     }
00108     // Final boundary conditions
00109     double qn = 0.0;
00110     u[n-1] = 0.0;
00111 
00112     // Back substitution loop of the tridiagonal algorithm
00113     yddot_data[n-1] = ( u[n-1] - qn*u[n-2]) / ( qn*yddot_data[n-2] + 1.0 );
00114     for ( int k = n-2; k >= 0; --k ) {
00115         yddot_data[k] = yddot_data[k]*yddot_data[k+1] + u[k];
00116     }
00117 }
00118 
00119 ecl::CubicSpline C2CubicSpline::instantiate() {
00120     CubicSpline cubic;
00121     apply(cubic);
00122     return cubic;
00123 };
00124 
00125 void C2CubicSpline::apply(ecl::CubicSpline& spline) const {
00126 
00127     spline.discretised_domain = x_data;
00128     spline.cubic_polynomials.resize(x_data.size()-1); // One less polynomials than there is points
00129     for (unsigned int i = 0; i < spline.cubic_polynomials.size(); ++i ) {
00130         spline.cubic_polynomials[i] = CubicPolynomial::SecondDerivativeInterpolation(
00131                         x_data[i],   y_data[i],   yddot_data[i],
00132                         x_data[i+1], y_data[i+1], yddot_data[i+1]  );
00133     }
00134 };
00135 
00136 
00137 /*****************************************************************************
00138 ** Implementation [DerivativeHeuristicCubicSpline]
00139 *****************************************************************************/
00140 
00141 DerivativeHeuristicCubicSpline::DerivativeHeuristicCubicSpline(const ecl::Array<double>& x_set, const ecl::Array<double>& y_set,
00142         const double ydot_0, const double ydot_f) ecl_assert_throw_decl(StandardException) :
00143         x_data(x_set),
00144         y_data(y_set)
00145 {
00146     ecl_assert_throw( x_data.size() == y_data.size(), StandardException(LOC,OutOfRangeError) );
00147     /*********************
00148     ** Via Velocities
00149     **********************/
00150     ydot_data.resize(x_data.size());
00151     ydot_data[0] = ydot_0;
00152     for (unsigned int i = 1; i < (x_data.size()-1); ++i ) { // Skip first and last.
00153         double ydot_before, ydot_after;
00154         ydot_before = (y_data[i]-y_data[i-1])/(x_data[i]-x_data[i-1]);
00155         ydot_after  = (y_data[i+1]-y_data[i])/(x_data[i+1]-x_data[i]);
00156         ydot_data[i] = (ydot_before + ydot_after)/2;
00157     }
00158     ydot_data[x_data.size()-1] = ydot_f;
00159 }
00160 
00161 ecl::CubicSpline DerivativeHeuristicCubicSpline::instantiate() {
00162     CubicSpline cubic;
00163     apply(cubic);
00164     return cubic;
00165 };
00166 
00167 void DerivativeHeuristicCubicSpline::apply(ecl::CubicSpline& spline) const {
00168 
00169     spline.discretised_domain = x_data;
00170     spline.cubic_polynomials.resize(x_data.size()-1); // One less polynomials than there is points
00171     for (unsigned int i = 0; i < spline.cubic_polynomials.size(); ++i ) {
00172         spline.cubic_polynomials[i] = CubicPolynomial::DerivativeInterpolation(
00173                         x_data[i],   y_data[i],   ydot_data[i],
00174                         x_data[i+1], y_data[i+1], ydot_data[i+1]  );
00175     }
00176 };
00177 
00178 } // namespace blueprints
00179 
00180 /*****************************************************************************
00181 ** Implementation [BluePrintFactory][CubicSpline]
00182 *****************************************************************************/
00183 
00184 using blueprints::C2CubicSpline;
00185 using blueprints::DerivativeHeuristicCubicSpline;
00186 
00187 C2CubicSpline BluePrintFactory< CubicSpline >::Natural(const Array<double>& x_set, const Array<double>& y_set) {
00188     return C2CubicSpline(x_set, y_set);
00189 };
00190 
00191             C2CubicSpline BluePrintFactory< CubicSpline >::ContinuousDerivatives(
00192             const Array<double>& x_set, const Array<double>& y_set, const double ydot_0, const double ydot_f) {
00193     return C2CubicSpline(x_set, y_set, ydot_0, ydot_f);
00194 };
00195 
00196 DerivativeHeuristicCubicSpline BluePrintFactory< CubicSpline >::DerivativeHeuristic(
00197             const Array<double>& x_set, const Array<double>& y_set, const double ydot_0, const double ydot_f) {
00198     return DerivativeHeuristicCubicSpline(x_set, y_set, ydot_0, ydot_f);
00199 }
00200 
00201 } // namespace ecl


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Mon Jul 3 2017 02:21:51