3th Order Runge-Kutta Integrator (explicit) More...
#include <explicit_integrators.h>

| 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 Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &x2, double dt, const UnaryFunction &fun, Eigen::Ref< Eigen::VectorXd > error) | 
| 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... | |
| 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 | 
| 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... | |
3th Order Runge-Kutta Integrator (explicit)
Refer to https://www.math.uni-hamburg.de/home/hofmann/lehrveranstaltungen/sommer05/prosem/Vortrag12.pdf
Definition at line 189 of file explicit_integrators.h.
| 
 | inlineoverridevirtual | 
Return the convergence order.
Implements corbo::NumericalIntegratorExplicitInterface.
Definition at line 196 of file explicit_integrators.h.
| 
 | inlineoverridevirtual | 
Return a newly created shared instance of the implemented class.
Implements corbo::NumericalIntegratorExplicitInterface.
Definition at line 193 of file explicit_integrators.h.
| 
 | inlineoverridevirtual | 
Allocate memory for a given state dimension.
| [in] | state_dim | Expected dimension of the state vector | 
Reimplemented from corbo::NumericalIntegratorExplicitInterface.
Definition at line 198 of file explicit_integrators.h.
| 
 | inlineoverride | 
Definition at line 206 of file explicit_integrators.h.
| 
 | inlineoverridevirtual | 
Solution of the initial value problem.
![\[ x(t=\Delta T) = \int_{t=0}^{t=\Delta T} f(x(t), u_1) dt \]](form_247.png) 
with $ x(t=0) = x_1 $.
| [in] | x1 | Initial state vector [SystemDynamicsInterface::getStateDimension() x 1] | 
| [in] | u1 | Constant control input vector [SystemDynamicsInterface::getInputDimension() x 1] | 
| [in] | dt | Time interval length | 
| [in] | system | System dynamics object | 
| [out] | x2 | Resulting state vector [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated) | 
Implements corbo::NumericalIntegratorExplicitInterface.
Definition at line 222 of file explicit_integrators.h.
| 
 | private | 
Definition at line 247 of file explicit_integrators.h.
| 
 | private | 
Definition at line 248 of file explicit_integrators.h.
| 
 | private | 
Definition at line 249 of file explicit_integrators.h.