Forward euler (explicit euler) integration. 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 | 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... | |
![]() | |
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) |
virtual void | initialize (int state_dim) |
Allocate memory for a given state dimension. 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... | |
![]() | |
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... | |
Additional Inherited Members | |
![]() | |
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 > |
![]() | |
using | InputVector = Eigen::VectorXd |
using | Ptr = std::shared_ptr< DynamicsEvalInterface > |
using | StateVector = Eigen::VectorXd |
using | UPtr = std::unique_ptr< DynamicsEvalInterface > |
![]() | |
static Factory< DynamicsEvalInterface > & | getFactory () |
Get access to the accociated factory. More... | |
Forward euler (explicit euler) integration.
.
Definition at line 47 of file explicit_integrators.h.
|
inlineoverridevirtual |
Return the convergence order.
Implements corbo::NumericalIntegratorExplicitInterface.
Definition at line 54 of file explicit_integrators.h.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Implements corbo::NumericalIntegratorExplicitInterface.
Definition at line 51 of file explicit_integrators.h.
|
inlineoverride |
Definition at line 57 of file explicit_integrators.h.
|
inlineoverridevirtual |
Solution of the initial value problem.
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 66 of file explicit_integrators.h.