Public Member Functions | Private Attributes | List of all members
corbo::IntegratorExplicitRungeKutta6 Class Reference

6th Order Runge-Kutta Integrator (explicit) More...

#include <explicit_integrators.h>

Inheritance diagram for corbo::IntegratorExplicitRungeKutta6:
Inheritance graph
[legend]

Public Member Functions

int getConvergenceOrder () const override
 Return the convergence order. More...
 
DynamicsEvalInterface::Ptr getInstance () const override
 Return a newly created shared instance of the implemented class. More...
 
void initialize (int state_dim) override
 Allocate memory for a given state dimension. More...
 
void solveIVP (const Eigen::VectorXd &x1, double dt, const std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> &fun, Eigen::Ref< Eigen::VectorXd > x2) override
 
void solveIVP (const StateVector &x1, const InputVector &u1, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > x2) override
 Solution of the initial value problem. More...
 
- Public Member Functions inherited from corbo::NumericalIntegratorExplicitInterface
void computeEqualityConstraint (const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
 Compute error between two consecutive (discrete) states. More...
 
void computeEqualityConstraint (const Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &x2, double dt, const UnaryFunction &fun, Eigen::Ref< Eigen::VectorXd > error)
 
bool interpolate (const Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &u1, const Eigen::Ref< const Eigen::VectorXd > &, const Eigen::Ref< const Eigen::VectorXd > &, double dt, const SystemDynamicsInterface &system, const Range &range, std::vector< Eigen::VectorXd > &states, std::vector< Eigen::VectorXd > &controls) override
 
virtual void solveIVP (const Eigen::VectorXd &x1, double dt, const UnaryFunction &fun, Eigen::Ref< Eigen::VectorXd > x2)=0
 Solution of the initial value problem. More...
 
virtual ~NumericalIntegratorExplicitInterface ()
 Virtual destructor. More...
 
- Public Member Functions inherited from corbo::DynamicsEvalInterface
virtual bool interpolate (const std::vector< const Eigen::VectorXd *> &x, const std::vector< const Eigen::VectorXd *> &u, double dt, const SystemDynamicsInterface &system, const Range &range, std::vector< Eigen::VectorXd > &states, std::vector< Eigen::VectorXd > &controls)
 
virtual ~DynamicsEvalInterface ()
 Virtual destructor. More...
 

Private Attributes

Eigen::VectorXd _k1
 
Eigen::VectorXd _k2
 
Eigen::VectorXd _k3
 
Eigen::VectorXd _k4
 
Eigen::VectorXd _k5
 
Eigen::VectorXd _k6
 
Eigen::VectorXd _k7
 
Eigen::VectorXd _k8
 

Additional Inherited Members

- Public Types inherited from corbo::NumericalIntegratorExplicitInterface
using Ptr = std::shared_ptr< NumericalIntegratorExplicitInterface >
 
using UnaryFunction = const std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)>
 
using UPtr = std::unique_ptr< NumericalIntegratorExplicitInterface >
 
- Public Types inherited from corbo::DynamicsEvalInterface
using InputVector = Eigen::VectorXd
 
using Ptr = std::shared_ptr< DynamicsEvalInterface >
 
using StateVector = Eigen::VectorXd
 
using UPtr = std::unique_ptr< DynamicsEvalInterface >
 
- Static Public Member Functions inherited from corbo::DynamicsEvalInterface
static Factory< DynamicsEvalInterface > & getFactory ()
 Get access to the accociated factory. More...
 

Detailed Description

6th Order Runge-Kutta Integrator (explicit)

For more information please refer to https://ntrs.nasa.gov/archive/nasa/casi.ntrs.nasa.gov/19680027281.pdf

See also
NumericalIntegratorInterface NumericalIntegratorExplicitInterface IntegratorExplicitRungeKutta6
Author
Alexander Westermann (alexa.nosp@m.nder.nosp@m..west.nosp@m.erma.nosp@m.nn@tu.nosp@m.-dor.nosp@m.tmund.nosp@m..de)

Definition at line 429 of file explicit_integrators.h.

Member Function Documentation

◆ getConvergenceOrder()

int corbo::IntegratorExplicitRungeKutta6::getConvergenceOrder ( ) const
inlineoverridevirtual

Return the convergence order.

Implements corbo::NumericalIntegratorExplicitInterface.

Definition at line 436 of file explicit_integrators.h.

◆ getInstance()

DynamicsEvalInterface::Ptr corbo::IntegratorExplicitRungeKutta6::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Implements corbo::NumericalIntegratorExplicitInterface.

Definition at line 433 of file explicit_integrators.h.

◆ initialize()

void corbo::IntegratorExplicitRungeKutta6::initialize ( int  state_dim)
inlineoverridevirtual

Allocate memory for a given state dimension.

Remarks
This method is optional and not guaranteed to be called, but if so this might speed up computation.
Parameters
[in]state_dimExpected dimension of the state vector

Reimplemented from corbo::NumericalIntegratorExplicitInterface.

Definition at line 438 of file explicit_integrators.h.

◆ solveIVP() [1/2]

void corbo::IntegratorExplicitRungeKutta6::solveIVP ( const Eigen::VectorXd &  x1,
double  dt,
const std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> &  fun,
Eigen::Ref< Eigen::VectorXd >  x2 
)
inlineoverride

Definition at line 451 of file explicit_integrators.h.

◆ solveIVP() [2/2]

void corbo::IntegratorExplicitRungeKutta6::solveIVP ( const StateVector x1,
const InputVector u1,
double  dt,
const SystemDynamicsInterface system,
Eigen::Ref< Eigen::VectorXd >  x2 
)
inlineoverridevirtual

Solution of the initial value problem.

\[ x(t=\Delta T) = \int_{t=0}^{t=\Delta T} f(x(t), u_1) dt \]

with $ x(t=0) = x_1 $.

Parameters
[in]x1Initial state vector [SystemDynamicsInterface::getStateDimension() x 1]
[in]u1Constant control input vector [SystemDynamicsInterface::getInputDimension() x 1]
[in]dtTime interval length
[in]systemSystem dynamics object
[out]x2Resulting state vector [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated)

Implements corbo::NumericalIntegratorExplicitInterface.

Definition at line 479 of file explicit_integrators.h.

Member Data Documentation

◆ _k1

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k1
private

Definition at line 517 of file explicit_integrators.h.

◆ _k2

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k2
private

Definition at line 518 of file explicit_integrators.h.

◆ _k3

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k3
private

Definition at line 519 of file explicit_integrators.h.

◆ _k4

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k4
private

Definition at line 520 of file explicit_integrators.h.

◆ _k5

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k5
private

Definition at line 521 of file explicit_integrators.h.

◆ _k6

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k6
private

Definition at line 522 of file explicit_integrators.h.

◆ _k7

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k7
private

Definition at line 523 of file explicit_integrators.h.

◆ _k8

Eigen::VectorXd corbo::IntegratorExplicitRungeKutta6::_k8
private

Definition at line 524 of file explicit_integrators.h.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:02