Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members

Implements a scheme for evaluating discretized ODEs. More...

#include <integrator_discretized_ode.hpp>

Inheritance diagram for IntegratorDiscretizedODE:
Inheritance graph
[legend]

Public Member Functions

virtual Integratorclone () const
 
virtual returnValue init (const DifferentialEquation &rhs_)
 
 IntegratorDiscretizedODE ()
 
 IntegratorDiscretizedODE (const DifferentialEquation &rhs_)
 
 IntegratorDiscretizedODE (const IntegratorDiscretizedODE &arg)
 
virtual IntegratorDiscretizedODEoperator= (const IntegratorDiscretizedODE &arg)
 
virtual returnValue step (int number)
 
virtual ~IntegratorDiscretizedODE ()
 
- Public Member Functions inherited from IntegratorRK12
 IntegratorRK12 ()
 
 IntegratorRK12 (const DifferentialEquation &rhs_)
 
 IntegratorRK12 (const IntegratorRK12 &arg)
 
virtual IntegratorRK12operator= (const IntegratorRK12 &arg)
 
virtual ~IntegratorRK12 ()
 
- Public Member Functions inherited from IntegratorRK
virtual returnValue freezeAll ()
 
virtual returnValue freezeMesh ()
 
virtual int getNumberOfRejectedSteps () const
 
virtual int getNumberOfSteps () const
 
virtual double getStepSize () const
 
returnValue init (const DifferentialEquation &rhs_, const Transition &trs_)
 
 IntegratorRK ()
 
 IntegratorRK (int dim_, double power_)
 
 IntegratorRK (const DifferentialEquation &rhs_, int dim_, double power_)
 
 IntegratorRK (const IntegratorRK &arg)
 
virtual IntegratorRKoperator= (const IntegratorRK &arg)
 
virtual returnValue setDxInitialization (double *dx0)
 
virtual returnValue stop ()
 
virtual returnValue unfreeze ()
 
virtual ~IntegratorRK ()
 
- Public Member Functions inherited from Integrator
virtual BooleanType canHandleImplicitSwitches () const
 
virtual returnValue deleteAllSeeds ()
 
returnValue getBackwardSensitivities (DVector &Dx_x0, DVector &Dx_p, DVector &Dx_u, DVector &Dx_w, int order) const
 
virtual double getDifferentialEquationSampleTime () const
 
returnValue getForwardSensitivities (DVector &Dx, int order) const
 
returnValue getForwardSensitivities (VariablesGrid &Dx, int order) const
 
returnValue getI (VariablesGrid &I) const
 
returnValue getX (DVector &xEnd) const
 
returnValue getX (VariablesGrid &X) const
 
returnValue getXA (DVector &xaEnd) const
 
returnValue getXA (VariablesGrid &XA) const
 
returnValue init (const DifferentialEquation &rhs, const Transition &trs)
 
returnValue integrate (double t0, double tend, double *x0, double *xa=0, double *p=0, double *u=0, double *w=0)
 
returnValue integrate (const Grid &t, double *x0, double *xa=0, double *p=0, double *u=0, double *w=0)
 
returnValue integrate (double t0, double tend, const DVector &x0, const DVector &xa=emptyVector, const DVector &p=emptyVector, const DVector &u=emptyVector, const DVector &w=emptyVector)
 
returnValue integrate (const Grid &t, const DVector &x0, const DVector &xa=emptyVector, const DVector &p=emptyVector, const DVector &u=emptyVector, const DVector &w=emptyVector)
 
returnValue integrateSensitivities ()
 
 Integrator ()
 
 Integrator (const Integrator &arg)
 
virtual BooleanType isDifferentialEquationAffine () const
 
virtual BooleanType isDifferentialEquationDefined () const
 
virtual returnValue printRunTimeProfile () const
 
returnValue setBackwardSeed (const int &order, const DVector &seed)
 
returnValue setForwardSeed (const int &order, const DVector &xSeed, const DVector &pSeed=emptyVector, const DVector &uSeed=emptyVector, const DVector &wSeed=emptyVector)
 
returnValue setTransition (const Transition &trs)
 
virtual ~Integrator ()
 
- Public Member Functions inherited from AlgorithmicBase
int addLogRecord (LogRecord &_record)
 
returnValue addOption (OptionsName name, int value)
 
returnValue addOption (OptionsName name, double value)
 
returnValue addOption (uint idx, OptionsName name, int value)
 
returnValue addOption (uint idx, OptionsName name, double value)
 
returnValue addOptionsList ()
 
 AlgorithmicBase ()
 
 AlgorithmicBase (UserInteraction *_userInteraction)
 
 AlgorithmicBase (const AlgorithmicBase &rhs)
 
returnValue get (OptionsName name, int &value) const
 
returnValue get (OptionsName name, double &value) const
 
returnValue get (OptionsName name, std::string &value) const
 
returnValue get (uint idx, OptionsName name, int &value) const
 
returnValue get (uint idx, OptionsName name, double &value) const
 
returnValue getAll (LogName _name, MatrixVariablesGrid &values) const
 
returnValue getFirst (LogName _name, DMatrix &firstValue) const
 
returnValue getFirst (LogName _name, VariablesGrid &firstValue) const
 
returnValue getLast (LogName _name, DMatrix &lastValue) const
 
returnValue getLast (LogName _name, VariablesGrid &lastValue) const
 
Options getOptions (uint idx) const
 
BooleanType haveOptionsChanged () const
 
BooleanType haveOptionsChanged (uint idx) const
 
AlgorithmicBaseoperator= (const AlgorithmicBase &rhs)
 
returnValue plot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
returnValue printLogRecord (std::ostream &_stream, int idx, LogPrintMode _mode=PRINT_ITEM_BY_ITEM) const
 
returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
returnValue set (OptionsName name, int value)
 
returnValue set (OptionsName name, double value)
 
returnValue set (OptionsName name, const std::string &value)
 
returnValue set (uint idx, OptionsName name, int value)
 
returnValue set (uint idx, OptionsName name, double value)
 
returnValue setAll (LogName _name, const MatrixVariablesGrid &values)
 
returnValue setLast (LogName _name, int lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, double lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const DVector &lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const DMatrix &lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const VariablesGrid &lastValue, double time=-INFTY)
 
returnValue setOptions (const Options &arg)
 
returnValue setOptions (uint idx, const Options &arg)
 
virtual ~AlgorithmicBase ()
 

Protected Member Functions

returnValue performADbackwardStep (const int &number_)
 
returnValue performADbackwardStep2 (const int &number_)
 
returnValue performADforwardStep (const int &number_)
 
returnValue performADforwardStep2 (const int &number_)
 
returnValue performDiscreteStep (const int &number_)
 
- Protected Member Functions inherited from IntegratorRK12
virtual void initializeButcherTableau ()
 
- Protected Member Functions inherited from IntegratorRK
void allocateMemory ()
 
void constructAll (const IntegratorRK &arg)
 
void deleteAll ()
 
double determineEta45 ()
 
double determineEta45 (int number)
 
void determineEtaGForward (int number)
 
void determineEtaGForward2 (int number)
 
void determineEtaHBackward (int number)
 
void determineEtaHBackward2 (int number)
 
virtual returnValue evaluate (const DVector &x0, const DVector &xa, const DVector &p, const DVector &u, const DVector &w, const Grid &t_)
 
virtual returnValue evaluateSensitivities ()
 
virtual int getDim () const
 
virtual returnValue getProtectedBackwardSensitivities (DVector &Dx_x0, DVector &Dx_p, DVector &Dx_u, DVector &Dx_w, int order) const
 
virtual returnValue getProtectedForwardSensitivities (DMatrix *Dx, int order) const
 
virtual returnValue getProtectedX (DVector *xEnd) const
 
void initializeVariables ()
 
void interpolate (int jj, double *e1, double *d1, double *e2, VariablesGrid &poly)
 
void logCurrentIntegratorStep (const DVector &currentX=emptyConstVector)
 
void printIntermediateResults ()
 
virtual returnValue setBackwardSeed2 (const DVector &seed)
 
returnValue setForwardSeed2 (const DVector &xSeed, const DVector &pSeed, const DVector &uSeed, const DVector &wSeed)
 
virtual returnValue setProtectedBackwardSeed (const DVector &seed, const int &order)
 
virtual returnValue setProtectedForwardSeed (const DVector &xSeed, const DVector &pSeed, const DVector &uSeed, const DVector &wSeed, const int &order)
 
- Protected Member Functions inherited from Integrator
virtual returnValue diffTransitionBackward (DVector &DX, DVector &DP, DVector &DU, DVector &DW, int &order)
 
virtual returnValue diffTransitionForward (DVector &DX, const DVector &DP, const DVector &DU, const DVector &DW, const int &order)
 
virtual returnValue evaluateTransition (const double time, DVector &xd, const DVector &xa, const DVector &p, const DVector &u, const DVector &w)
 
virtual int getDimX () const
 
void initializeOptions ()
 
virtual returnValue setupLogging ()
 
virtual returnValue setupOptions ()
 

Protected Attributes

double stepLength
 
- Protected Attributes inherited from IntegratorRK
double ** A
 
double * b4
 
double * b5
 
DVector bseed
 
DVector bseed2
 
double * c
 
int dim
 
double err_power
 
double * eta4
 
double * eta4_
 
double * eta5
 
double * eta5_
 
double * etaG
 
double * etaG2
 
double * etaG3
 
double * etaH
 
double * etaH2
 
double * etaH3
 
DVector fseed
 
DVector fseed2
 
double * G
 
double * G2
 
double * G3
 
double * H
 
double * H2
 
double * H3
 
double ** k
 
double ** k2
 
double ** l
 
double ** l2
 
int maxAlloc
 
double t
 
double * x
 
- Protected Attributes inherited from Integrator
int * alg_index
 
int * control_index
 
int count
 
int count2
 
int count3
 
int * ddiff_index
 
VariablesGrid ddxStore
 
int * diff_index
 
DVector diff_scale
 
int * disturbance_index
 
DVector dP
 
DVector dPb
 
DVector dU
 
DVector dUb
 
DVector dW
 
DVector dWb
 
DVector dX
 
DVector dXb
 
VariablesGrid dxStore
 
RealClock functionEvaluation
 
double * h
 
double hini
 
double hmax
 
double hmin
 
int * int_control_index
 
int * int_parameter_index
 
VariablesGrid iStore
 
int las
 
short int m
 
short int ma
 
int maxNumberOfSteps
 
short int md
 
short int mdx
 
short int mn
 
short int mp
 
short int mpi
 
short int mu
 
short int mui
 
short int mw
 
int nBDirs
 
int nBDirs2
 
int nFcnEvaluations
 
int nFDirs
 
int nFDirs2
 
int * parameter_index
 
int PrintLevel
 
DifferentialEquationrhs
 
StateOfAggregation soa
 
int time_index
 
Grid timeInterval
 
double TOL
 
RealClock totalTime
 
Transitiontransition
 
double tune
 
DVector xE
 
VariablesGrid xStore
 
- Protected Attributes inherited from AlgorithmicBase
int outputLoggingIdx
 
BooleanType useModuleStandalone
 
UserInteractionuserInteraction
 

Friends

class ShootingMethod
 

Detailed Description

Implements a scheme for evaluating discretized ODEs.

The class IntegratorDiscretizedODE implements a scheme for evaluating discretized ordinary differential equations (ODEs).

Author
Boris Houska, Hans Joachim Ferreau

Definition at line 57 of file integrator_discretized_ode.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO IntegratorDiscretizedODE::IntegratorDiscretizedODE ( )

Default constructor.

Definition at line 53 of file integrator_discretized_ode.cpp.

IntegratorDiscretizedODE::IntegratorDiscretizedODE ( const DifferentialEquation rhs_)

Default constructor.

Definition at line 58 of file integrator_discretized_ode.cpp.

IntegratorDiscretizedODE::IntegratorDiscretizedODE ( const IntegratorDiscretizedODE arg)

Copy constructor (deep copy).

Definition at line 74 of file integrator_discretized_ode.cpp.

IntegratorDiscretizedODE::~IntegratorDiscretizedODE ( )
virtual

Destructor.

Definition at line 81 of file integrator_discretized_ode.cpp.

Member Function Documentation

Integrator * IntegratorDiscretizedODE::clone ( ) const
virtual

The (virtual) copy constructor

Reimplemented from IntegratorRK12.

Definition at line 96 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::init ( const DifferentialEquation rhs_)
virtual

The initialization routine which takes the right-hand side of
the differential equation to be integrated.

Parameters
rhsthe right-hand side of the ODE/DAE.

Returns
SUCCESSFUL_RETURN if all dimension checks succeed.
otherwise: integrator dependent error message.

Reimplemented from IntegratorRK12.

Definition at line 103 of file integrator_discretized_ode.cpp.

IntegratorDiscretizedODE & IntegratorDiscretizedODE::operator= ( const IntegratorDiscretizedODE arg)
virtual

Assignment operator (deep copy).

Definition at line 86 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::performADbackwardStep ( const int &  number_)
protected

Definition at line 296 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::performADbackwardStep2 ( const int &  number_)
protected

Definition at line 343 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::performADforwardStep ( const int &  number_)
protected

Definition at line 275 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::performADforwardStep2 ( const int &  number_)
protected

Definition at line 321 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::performDiscreteStep ( const int &  number_)
protected

Definition at line 255 of file integrator_discretized_ode.cpp.

returnValue IntegratorDiscretizedODE::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

Returns
RET_FINAL_STEP_NOT_PERFORMED_YET
for the case that the final step has not been
performed yet, i.e. the integration routine is not yet
at the time tend.
Otherwise it will either return
SUCCESSFUL_RETURN
or any other error message that might occur during
an integration step.
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.)
Parameters
numberthe step number

Reimplemented from IntegratorRK12.

Definition at line 111 of file integrator_discretized_ode.cpp.

Friends And Related Function Documentation

friend class ShootingMethod
friend

Definition at line 60 of file integrator_discretized_ode.hpp.

Member Data Documentation

double IntegratorDiscretizedODE::stepLength
protected

Definition at line 113 of file integrator_discretized_ode.hpp.


The documentation for this class was generated from the following files:


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:25