Implements the backward-differentiation formula for integrating DAEs. More...
#include <integrator_bdf.hpp>
Implements the backward-differentiation formula for integrating DAEs.
The class IntegratorBDF implements the backward-differentiation formula for integrating differential-algebraic equations (DAEs).
Definition at line 52 of file integrator_bdf.hpp.
Default constructor.
Definition at line 49 of file integrator_bdf.cpp.
IntegratorBDF::IntegratorBDF | ( | const DifferentialEquation & | rhs_ | ) |
Default constructor.
Definition at line 56 of file integrator_bdf.cpp.
IntegratorBDF::IntegratorBDF | ( | const IntegratorBDF & | arg | ) |
Copy constructor (deep copy).
Definition at line 62 of file integrator_bdf.cpp.
IntegratorBDF::~IntegratorBDF | ( | ) | [virtual] |
Destructor.
Definition at line 70 of file integrator_bdf.cpp.
void IntegratorBDF::allocateMemory | ( | ) | [protected] |
This routine is protected and sets up all
variables (i.e. allocates memory etc.).
Note that this routine assumes that the
dimensions are already set correctly and is
thus for internal use only.
Definition at line 111 of file integrator_bdf.cpp.
void IntegratorBDF::applyMTranspose | ( | int | index, |
double * | seed1, | ||
DMatrix & | J, | ||
double * | seed2 | ||
) | [protected] |
applies the transpose of M (needed for automatic differentiation
in backward mode)
Definition at line 5168 of file integrator_bdf.cpp.
double IntegratorBDF::applyNewtonStep | ( | int | index, |
double * | etakplus1, | ||
const double * | etak, | ||
const DMatrix & | J, | ||
const double * | FFF | ||
) | [protected] |
applies a newton step
Definition at line 5140 of file integrator_bdf.cpp.
Integrator * IntegratorBDF::clone | ( | ) | const [virtual] |
The (virtual) copy constructor
Implements Integrator.
Definition at line 792 of file integrator_bdf.cpp.
void IntegratorBDF::constructAll | ( | const IntegratorBDF & | arg | ) | [protected] |
Protected implementation of the copy constructor.
Definition at line 446 of file integrator_bdf.cpp.
void IntegratorBDF::copyBackward | ( | DVector & | Dx_x0, |
DVector & | Dx_p, | ||
DVector & | Dx_u, | ||
DVector & | Dx_w, | ||
const DMatrix & | div | ||
) | const [protected] |
Definition at line 5282 of file integrator_bdf.cpp.
returnValue IntegratorBDF::decomposeJacobian | ( | int | index, |
DMatrix & | J | ||
) | [protected] |
Decomposes the Jacobian J.
Definition at line 5114 of file integrator_bdf.cpp.
void IntegratorBDF::deleteAll | ( | ) | [protected] |
Delete everything.
Definition at line 798 of file integrator_bdf.cpp.
void IntegratorBDF::determineBDFEtaGForward | ( | int | number | ) | [protected] |
Differentiation of the BDF step:
Definition at line 4353 of file integrator_bdf.cpp.
void IntegratorBDF::determineBDFEtaGForward2 | ( | int | number | ) | [protected] |
Differentiation of the BDF step:
Definition at line 4532 of file integrator_bdf.cpp.
void IntegratorBDF::determineBDFEtaHBackward | ( | int | number | ) | [protected] |
Differentiation of the BDF step:
Definition at line 4444 of file integrator_bdf.cpp.
void IntegratorBDF::determineBDFEtaHBackward2 | ( | int | number | ) | [protected] |
Differentiation of the BDF step:
Definition at line 4671 of file integrator_bdf.cpp.
returnValue IntegratorBDF::determineCorrector | ( | int | number, |
BooleanType | ini | ||
) | [protected] |
determines the predictor and corrector polynom
Definition at line 2344 of file integrator_bdf.cpp.
double IntegratorBDF::determinePredictor | ( | int | number, |
BooleanType | ini | ||
) | [protected] |
determines the predictor and starts the corrector iterations.
If a corrector is found a local error estimate will be returned.
Definition at line 2231 of file integrator_bdf.cpp.
void IntegratorBDF::determineRKEtaGForward | ( | ) | [protected] |
Differentiation of the RK-Starter:
Definition at line 3029 of file integrator_bdf.cpp.
void IntegratorBDF::determineRKEtaGForward2 | ( | ) | [protected] |
Differentiation of the RK-Starter:
Definition at line 3567 of file integrator_bdf.cpp.
void IntegratorBDF::determineRKEtaHBackward | ( | ) | [protected] |
Differentiation of the RK-Starter:
Definition at line 3103 of file integrator_bdf.cpp.
void IntegratorBDF::determineRKEtaHBackward2 | ( | ) | [protected] |
Differentiation of the RK-Starter:
Definition at line 3657 of file integrator_bdf.cpp.
returnValue IntegratorBDF::evaluate | ( | const DVector & | x0, |
const DVector & | xa, | ||
const DVector & | p, | ||
const DVector & | u, | ||
const DVector & | w, | ||
const Grid & | t_ | ||
) | [protected, virtual] |
Starts integration: cf. integrate(...) for
more details.
x0 | the initial state |
xa | the initial algebraic state |
p | the parameters |
u | the controls |
w | the disturbance |
t_ | the time interval |
Implements Integrator.
Definition at line 1112 of file integrator_bdf.cpp.
returnValue IntegratorBDF::evaluateSensitivities | ( | ) | [protected, virtual] |
< Integrates forward and/or backward depending on the specified seeds.
Implements Integrator.
Definition at line 1650 of file integrator_bdf.cpp.
returnValue IntegratorBDF::freezeAll | ( | ) | [virtual] |
Freezes the mesh as well as all intermediate values. This function
is necessary for the case that automatic differentiation in backward
mode should is used. (Note: This function might for large right hand
sides lead to memory problems as all intemediate values will be
stored!)
Implements Integrator.
Definition at line 1047 of file integrator_bdf.cpp.
returnValue IntegratorBDF::freezeMesh | ( | ) | [virtual] |
Freezes the mesh: Storage of the step sizes. If the integrator is
freezed the mesh will be stored when calling the function integrate
for the first time. If the function integrate is called more than
once the same mesh will be reused (i.e. the step size control will
be turned off). Note that the mesh should be frozen if any kind of
sensitivity generation is used.
Implements Integrator.
Definition at line 1032 of file integrator_bdf.cpp.
int IntegratorBDF::getDim | ( | ) | const [protected, virtual] |
Returns the dimension of the Differential Equation
Implements Integrator.
Definition at line 5250 of file integrator_bdf.cpp.
int IntegratorBDF::getDimX | ( | ) | const [protected, virtual] |
Returns the number of Dynamic Equations in the Differential Equation
Reimplemented from Integrator.
Definition at line 5255 of file integrator_bdf.cpp.
int IntegratorBDF::getNumberOfRejectedSteps | ( | ) | const [virtual] |
Returns the number of rejected Steps.
Implements Integrator.
Definition at line 2211 of file integrator_bdf.cpp.
int IntegratorBDF::getNumberOfSteps | ( | ) | const [virtual] |
Returns the number of accepted Steps.
Implements Integrator.
Definition at line 2206 of file integrator_bdf.cpp.
returnValue IntegratorBDF::getProtectedBackwardSensitivities | ( | DVector & | Dx_x0, |
DVector & | Dx_p, | ||
DVector & | Dx_u, | ||
DVector & | Dx_w, | ||
int | order | ||
) | const [protected, virtual] |
Returns the result for the backward sensitivities at the time tend.
Dx_x0 | backward sensitivities w.r.t. the initial states |
Dx_p | backward sensitivities w.r.t. the parameters |
Dx_u | backward sensitivities w.r.t. the controls |
Dx_w | backward sensitivities w.r.t. the disturbance |
order | the order of the derivative |
Implements Integrator.
Definition at line 2158 of file integrator_bdf.cpp.
returnValue IntegratorBDF::getProtectedForwardSensitivities | ( | DMatrix * | Dx, |
int | order | ||
) | const [protected, virtual] |
Returns the result for the forward sensitivities at the time tend.
Dx | the result for the forward sensitivi- ties |
order | the order |
Definition at line 2106 of file integrator_bdf.cpp.
returnValue IntegratorBDF::getProtectedX | ( | DVector * | xEnd | ) | const [protected, virtual] |
Returns the result for the state at the time tend.
xEnd | the result for the states at the time tend. |
Implements Integrator.
Definition at line 2092 of file integrator_bdf.cpp.
double IntegratorBDF::getStepSize | ( | ) | const [virtual] |
Returns the current step size
Implements Integrator.
Definition at line 2219 of file integrator_bdf.cpp.
returnValue IntegratorBDF::init | ( | const DifferentialEquation & | rhs_ | ) | [virtual] |
The initialization routine which takes the right-hand side of
the differential equation to be integrated.
rhs | the right-hand side of the ODE/DAE. |
Implements Integrator.
Definition at line 88 of file integrator_bdf.cpp.
returnValue IntegratorBDF::init | ( | const DifferentialEquation & | rhs_, |
const Transition & | trs_ | ||
) | [inline] |
The initialization routine which takes the right-hand side of
the differential equation to be integrated. In addition a
transition function can be set which is evaluated at the end
of the integration interval.
rhs | the right-hand side of the ODE/DAE. |
trs | the transition to be evaluated at the end. |
Reimplemented from Integrator.
void IntegratorBDF::initializeButcherTableau | ( | ) | [protected] |
inializes the Butcher Tableau. (only for internal use)
Definition at line 4802 of file integrator_bdf.cpp.
void IntegratorBDF::initializeVariables | ( | ) | [protected] |
This routine is protected and is basically used
to set all pointer-valued member to the NULL pointer.
In addition some dimensions are initialized with 0 as
a default value.
Definition at line 409 of file integrator_bdf.cpp.
void IntegratorBDF::interpolate | ( | int | number_, |
DMatrix & | div, | ||
VariablesGrid & | poly | ||
) | [protected] |
Definition at line 5310 of file integrator_bdf.cpp.
void IntegratorBDF::logCurrentIntegratorStep | ( | const DVector & | currentX = emptyConstVector , |
const DVector & | currentXA = emptyConstVector |
||
) | [protected] |
Definition at line 5341 of file integrator_bdf.cpp.
IntegratorBDF & IntegratorBDF::operator= | ( | const IntegratorBDF & | arg | ) | [virtual] |
Assignment operator (deep copy).
Definition at line 76 of file integrator_bdf.cpp.
void IntegratorBDF::prepareDividedDifferences | ( | DMatrix & | div | ) | [protected] |
Definition at line 5261 of file integrator_bdf.cpp.
void IntegratorBDF::printBDFfinalResults | ( | ) | [protected] |
prints final results of the BDF steps.
Definition at line 4924 of file integrator_bdf.cpp.
void IntegratorBDF::printBDFfinalResults2 | ( | DMatrix & | div | ) | [protected] |
prints final results of the BDF steps.
Definition at line 4889 of file integrator_bdf.cpp.
void IntegratorBDF::printBDFIntermediateResults | ( | ) | [protected] |
prints intermediate results of the BDF steps.
Definition at line 4981 of file integrator_bdf.cpp.
void IntegratorBDF::printRKIntermediateResults | ( | ) | [protected] |
prints intermediate results of the Runge Kutta starter
Definition at line 5037 of file integrator_bdf.cpp.
void IntegratorBDF::relaxAlgebraic | ( | double * | residuum, |
double | timePoint | ||
) | [protected] |
Relax the algebraic equations
Definition at line 5203 of file integrator_bdf.cpp.
returnValue IntegratorBDF::rk_start | ( | ) | [protected] |
computes start values using a diagonal implicit RK-method.
Definition at line 2520 of file integrator_bdf.cpp.
returnValue IntegratorBDF::rk_start_solve | ( | int | stepnumber | ) | [protected] |
starts the newton iteration for the implicit computation of k
Definition at line 2839 of file integrator_bdf.cpp.
returnValue IntegratorBDF::setBackwardSeed2 | ( | const DVector & | seed | ) | [protected, virtual] |
Initializes a second backward seed. (only for internal use)
seed | the seed matrix |
Definition at line 1566 of file integrator_bdf.cpp.
returnValue IntegratorBDF::setDxInitialization | ( | double * | dx0 | ) | [virtual] |
Sets an initial guess for the differential state derivatives
(consistency condition)
dx0 | initial guess for the differential state derivatives |
Implements Integrator.
Definition at line 2181 of file integrator_bdf.cpp.
returnValue IntegratorBDF::setForwardSeed2 | ( | const DVector & | xSeed, |
const DVector & | pSeed, | ||
const DVector & | uSeed, | ||
const DVector & | wSeed | ||
) | [protected] |
Initializes a second forward seed. (only for internal use)
xSeed | the seed w.r.t the initial states |
pSeed | the seed w.r.t the parameters |
uSeed | the seed w.r.t the controls |
wSeed | the seed w.r.t the disturbances |
Definition at line 1429 of file integrator_bdf.cpp.
returnValue IntegratorBDF::setProtectedBackwardSeed | ( | const DVector & | seed, |
const int & | order | ||
) | [protected, virtual] |
Define a backward seed
seed | the seed matrix |
order | the order of the seed. |
Implements Integrator.
Definition at line 1503 of file integrator_bdf.cpp.
returnValue IntegratorBDF::setProtectedForwardSeed | ( | const DVector & | xSeed, |
const DVector & | pSeed, | ||
const DVector & | uSeed, | ||
const DVector & | wSeed, | ||
const int & | order | ||
) | [protected, virtual] |
Define a forward seed matrix.
xSeed | the seed w.r.t the initial states |
pSeed | the seed w.r.t the parameters |
uSeed | the seed w.r.t the controls |
wSeed | the seed w.r.t the disturbances |
order | the order of the seed. |
Implements Integrator.
Definition at line 1359 of file integrator_bdf.cpp.
returnValue IntegratorBDF::step | ( | int | number | ) | [virtual] |
Executes the next single step. This function can be used to
call the integrator step wise. Note that this function is e.g.
useful in real-time simulations where after each step a time
out limit has to be checked. This function will usually return
In most real situations you can define the maximum number of
step sizes to be 1 before calling the function integrate
Then the function integrate should return after one step with
the message
RET_MAXIMUM_NUMBER_OF_STEPS_EXCEEDED. After that you can call
step() until the final time is reached.
(You can use the PrintLevel NONE to avoid that the message
RET_MAXIMUM_NUMBER_OF_STEPS_EXCEEDED is printed.)
number | the step number |
Definition at line 1787 of file integrator_bdf.cpp.
returnValue IntegratorBDF::stop | ( | ) | [virtual] |
Stops the integration even if the final time has not been
reached yet. This function will also give all memory free.
In particular, the function unfreeze() will be called.
(This function is designed for the usage in real-time
contexts in order to deal with error messages without
deleting and re-initializing the integrator.)
Definition at line 2085 of file integrator_bdf.cpp.
returnValue IntegratorBDF::unfreeze | ( | ) | [virtual] |
Unfreezes the mesh: Gives the memory free that has previously
been allocated by "freeze". If you use the function
integrate after unfreezing the usual step size control will be
switched on.
Implements Integrator.
Definition at line 1061 of file integrator_bdf.cpp.
friend class ShootingMethod [friend] |
Reimplemented from Integrator.
Definition at line 56 of file integrator_bdf.hpp.
friend class SimulationByIntegration [friend] |
Reimplemented from Integrator.
Definition at line 55 of file integrator_bdf.hpp.
double** IntegratorBDF::A [protected] |
the coefficient A of the Butcher Tableau.
Definition at line 517 of file integrator_bdf.hpp.
double* IntegratorBDF::b4 [protected] |
the 4th order coefficients of the Butcher Tableau.
Definition at line 518 of file integrator_bdf.hpp.
double* IntegratorBDF::b5 [protected] |
the 5th order coefficients of the Butcher Tableau.
Definition at line 519 of file integrator_bdf.hpp.
DVector IntegratorBDF::bseed [protected] |
The backward seed (only internal use)
Definition at line 576 of file integrator_bdf.hpp.
DVector IntegratorBDF::bseed2 [protected] |
The backward seed 2 (only internal use)
Definition at line 579 of file integrator_bdf.hpp.
double* IntegratorBDF::c [protected] |
the time coefficients of the Butcher Tableau.
Definition at line 520 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2 [protected] |
the constant in the derivative of the corrector
polynom.
Definition at line 546 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2G [protected] |
Sensitivity matrix (only internal use)
Definition at line 586 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2G2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 598 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2G3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 599 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2H [protected] |
Sensitivity matrix (only internal use)
Definition at line 606 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2H2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 620 of file integrator_bdf.hpp.
DVector IntegratorBDF::c2H3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 621 of file integrator_bdf.hpp.
RealClock IntegratorBDF::correctorTime [protected] |
Definition at line 638 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::delta [protected] |
sums over the modified divided differences
Definition at line 545 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::deltaG [protected] |
Sensitivity matrix (only internal use)
Definition at line 585 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::deltaG2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 596 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::deltaG3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 597 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::deltaH [protected] |
Sensitivity matrix (only internal use)
Definition at line 605 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::deltaH2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 618 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::deltaH3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 619 of file integrator_bdf.hpp.
int IntegratorBDF::dim [protected] |
the dimension of the Butcher Tableau.
Definition at line 516 of file integrator_bdf.hpp.
double** IntegratorBDF::eta [protected] |
the predictor and corrector approximations
Definition at line 556 of file integrator_bdf.hpp.
double** IntegratorBDF::eta2 [protected] |
the predictor and corrector approximations
Definition at line 557 of file integrator_bdf.hpp.
double* IntegratorBDF::eta4 [protected] |
the result of order 4
Definition at line 525 of file integrator_bdf.hpp.
double* IntegratorBDF::eta4_ [protected] |
the result of order 4
Definition at line 527 of file integrator_bdf.hpp.
double* IntegratorBDF::eta5 [protected] |
the result of order 5
Definition at line 526 of file integrator_bdf.hpp.
double* IntegratorBDF::eta5_ [protected] |
the result of order 5
Definition at line 528 of file integrator_bdf.hpp.
double* IntegratorBDF::etaG [protected] |
Sensitivity matrix (only internal use)
Definition at line 582 of file integrator_bdf.hpp.
double* IntegratorBDF::etaG2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 590 of file integrator_bdf.hpp.
double* IntegratorBDF::etaG3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 591 of file integrator_bdf.hpp.
double** IntegratorBDF::etaH [protected] |
Sensitivity matrix (only internal use)
Definition at line 602 of file integrator_bdf.hpp.
double** IntegratorBDF::etaH2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 612 of file integrator_bdf.hpp.
double** IntegratorBDF::etaH3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 613 of file integrator_bdf.hpp.
double* IntegratorBDF::F [protected] |
Definition at line 561 of file integrator_bdf.hpp.
double* IntegratorBDF::F2 [protected] |
Definition at line 562 of file integrator_bdf.hpp.
DVector IntegratorBDF::fseed [protected] |
The forward seed (only internal use)
Definition at line 575 of file integrator_bdf.hpp.
DVector IntegratorBDF::fseed2 [protected] |
The forward seed 2 (only internal use)
Definition at line 578 of file integrator_bdf.hpp.
double* IntegratorBDF::G [protected] |
Sensitivity matrix (only internal use)
Definition at line 581 of file integrator_bdf.hpp.
double* IntegratorBDF::G2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 588 of file integrator_bdf.hpp.
double* IntegratorBDF::G3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 589 of file integrator_bdf.hpp.
double** IntegratorBDF::gamma [protected] |
intermediate coefficients
Definition at line 541 of file integrator_bdf.hpp.
double* IntegratorBDF::H [protected] |
Sensitivity matrix (only internal use)
Definition at line 601 of file integrator_bdf.hpp.
double* IntegratorBDF::H2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 610 of file integrator_bdf.hpp.
double* IntegratorBDF::H3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 611 of file integrator_bdf.hpp.
double* IntegratorBDF::initial_guess [protected] |
an initial guess for dot_x and xa
Definition at line 567 of file integrator_bdf.hpp.
double* IntegratorBDF::initialAlgebraicResiduum [protected] |
Definition at line 509 of file integrator_bdf.hpp.
double* IntegratorBDF::iseed [protected] |
the intermediate seeds
Definition at line 533 of file integrator_bdf.hpp.
RealClock IntegratorBDF::jacComputation [protected] |
Definition at line 636 of file integrator_bdf.hpp.
RealClock IntegratorBDF::jacDecomposition [protected] |
Definition at line 637 of file integrator_bdf.hpp.
double*** IntegratorBDF::k [protected] |
the intermediate results
Definition at line 529 of file integrator_bdf.hpp.
double*** IntegratorBDF::k2 [protected] |
the intermediate results
Definition at line 530 of file integrator_bdf.hpp.
double*** IntegratorBDF::kH [protected] |
Sensitivity matrix (only internal use)
Definition at line 607 of file integrator_bdf.hpp.
double*** IntegratorBDF::kH2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 622 of file integrator_bdf.hpp.
double*** IntegratorBDF::kH3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 624 of file integrator_bdf.hpp.
double*** IntegratorBDF::l [protected] |
the intermediate results
Definition at line 531 of file integrator_bdf.hpp.
double*** IntegratorBDF::l2 [protected] |
the intermediate results
Definition at line 532 of file integrator_bdf.hpp.
DMatrix** IntegratorBDF::M [protected] |
the Jacobians for Newton's method
Definition at line 549 of file integrator_bdf.hpp.
int* IntegratorBDF::M_index [protected] |
the index of the inverse approximation
Definition at line 551 of file integrator_bdf.hpp.
int IntegratorBDF::maxAlloc [protected] |
size of the memory that is allocated to store
the trajectory and the mesh.
Definition at line 630 of file integrator_bdf.hpp.
int IntegratorBDF::maxNM [protected] |
number of allocated Jacobian storage positions
Definition at line 553 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaG [protected] |
Sensitivity matrix (only internal use)
Definition at line 583 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaG2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 592 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaG3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 593 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaH [protected] |
Sensitivity matrix (only internal use)
Definition at line 603 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaH2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 614 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaH2_ [protected] |
Sensitivity matrix (only internal use)
Definition at line 616 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaH3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 615 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaH3_ [protected] |
Sensitivity matrix (only internal use)
Definition at line 617 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaH_ [protected] |
Sensitivity matrix (only internal use)
Definition at line 604 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaY [protected] |
the devided differences
Definition at line 542 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::nablaY_ [protected] |
the devided differences (backup)
Definition at line 543 of file integrator_bdf.hpp.
int IntegratorBDF::ndir [protected] |
number of dependecy directions (only internal use)
Definition at line 573 of file integrator_bdf.hpp.
int IntegratorBDF::nJacEvaluations [protected] |
Definition at line 639 of file integrator_bdf.hpp.
int IntegratorBDF::nOfM [protected] |
number of distinct inverse Jacobian approximations
Definition at line 552 of file integrator_bdf.hpp.
int* IntegratorBDF::nOfNewtonSteps [protected] |
the number of newton steps (for each BDF-step)
Definition at line 555 of file integrator_bdf.hpp.
int IntegratorBDF::nstep [protected] |
the horizon length of the multistep method
Definition at line 538 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::phi [protected] |
the modified divided differences
Definition at line 544 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::phiG [protected] |
Sensitivity matrix (only internal use)
Definition at line 584 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::phiG2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 594 of file integrator_bdf.hpp.
DMatrix IntegratorBDF::phiG3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 595 of file integrator_bdf.hpp.
double** IntegratorBDF::psi [protected] |
the time differences (multi-step-sizes).
Definition at line 539 of file integrator_bdf.hpp.
double* IntegratorBDF::psi_ [protected] |
the time differences (multi-step-sizes). (backup)
Definition at line 540 of file integrator_bdf.hpp.
double IntegratorBDF::rel_time_scale [protected] |
relative time scale (intermediate variable)
Definition at line 568 of file integrator_bdf.hpp.
double IntegratorBDF::relaxationConstant [protected] |
Definition at line 510 of file integrator_bdf.hpp.
double IntegratorBDF::t [protected] |
the actual time
Definition at line 558 of file integrator_bdf.hpp.
double* IntegratorBDF::x [protected] |
the actual state (only internal use)
Definition at line 559 of file integrator_bdf.hpp.
double** IntegratorBDF::zH [protected] |
Sensitivity matrix (only internal use)
Definition at line 608 of file integrator_bdf.hpp.
double** IntegratorBDF::zH2 [protected] |
Sensitivity matrix (only internal use)
Definition at line 623 of file integrator_bdf.hpp.
double** IntegratorBDF::zH3 [protected] |
Sensitivity matrix (only internal use)
Definition at line 625 of file integrator_bdf.hpp.