Interface for numerical integrators (explicit and implicit) More...
#include <integrator_interface.h>
Public Types | |
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 > |
Public Member Functions | |
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 int | getConvergenceOrder () const =0 |
Return the convergence order. More... | |
DynamicsEvalInterface::Ptr | getInstance () const override=0 |
Return a newly created shared instance of the implemented class. More... | |
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 void | solveIVP (const StateVector &x1, const InputVector &u1, double dt, const SystemDynamicsInterface &system, 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 | |
![]() | |
static Factory< DynamicsEvalInterface > & | getFactory () |
Get access to the accociated factory. More... | |
Interface for numerical integrators (explicit and implicit)
Explicit numerical integrators in the context of ordinary or partial differential equations determine the integral value only based on the previous or current time instance, e.g.:
.
Implicit methods require the solution of a (nonlinear) equation, since they also depend on the solution itself:
.
This generic interface mainly provides access to the underlying quadrature rules. These might be used as part of an optimization or might be solved via root-finding directly. For a direct use of integrators you might refer to the subclass NumericalIntegratorExplicitInterface. @remark This interface is provided with factory support. @see NumericalIntegratorExplicitInterface FiniteDifferencesInterface @author Christoph Rösmann (christoph.roesmann@tu-dortmund.de)
Allocate memory for a given state dimension
[in] | state_dim | Expected dimension of the state vector Compute equality constraint containing the implicit quadrature/interpolation formula (system dynamics specialization) |
.
@param[in] x1 Initial state vector [SystemDynamicsInterface::getStateDimension() x 1] @param[in] u1 Constant control input vector [SystemDynamicsInterface::getInputDimension() x 1] @param[in] x2 Final state vector [SystemDynamicsInterface::getStateDimension() x 1] @param[in] dt Time interval length @param[in] system System dynamics object @param[out] error Resulting error [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated)
Compute equality constraint containing the implicit quadrature/interpolation formula (unary function specialization)
.
@param[in] x1 Initial function argument @param[in] x2 Final function argument @param[in] dt Time interval length @param[in] fun f(x) to be integrated in the interval [0, dt] @param[out] error Resulting error [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated)
Interface for explicit numerical integrators
Explicit numerical integrators in the context of ordinary or partial differential equations determine the integral value only based on the previous or current time instance, e.g.:
.
Definition at line 158 of file integrator_interface.h.
using corbo::NumericalIntegratorExplicitInterface::Ptr = std::shared_ptr<NumericalIntegratorExplicitInterface> |
Definition at line 161 of file integrator_interface.h.
using corbo::NumericalIntegratorExplicitInterface::UnaryFunction = const std::function<void(const Eigen::VectorXd&, Eigen::Ref<Eigen::VectorXd>)> |
Definition at line 164 of file integrator_interface.h.
using corbo::NumericalIntegratorExplicitInterface::UPtr = std::unique_ptr<NumericalIntegratorExplicitInterface> |
Definition at line 162 of file integrator_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 169 of file integrator_interface.h.
|
inlineoverridevirtual |
Compute error between two consecutive (discrete) states.
.
error
and all other parameters![in] | x1 | Initial state vector [SystemDynamicsInterface::getStateDimension() x 1] |
[in] | u1 | Constant control input vector [SystemDynamicsInterface::getInputDimension() x 1] |
[in] | x2 | Final state vector [SystemDynamicsInterface::getStateDimension() x 1] |
[in] | dt | Time interval length |
[in] | system | System dynamics object |
[out] | error | Resulting error [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated) |
Implements corbo::DynamicsEvalInterface.
Definition at line 217 of file integrator_interface.h.
|
inline |
Definition at line 224 of file integrator_interface.h.
|
pure virtual |
Return the convergence order.
Implemented in corbo::IntegratorMultiStageScaled, corbo::IntegratorMultiStageFixedStep, corbo::IntegratorAdaptiveStepSize, corbo::IntegratorExplicitRungeKutta7, corbo::IntegratorExplicitRungeKutta6, corbo::IntegratorExplicitRungeKutta5, corbo::IntegratorExplicitRungeKutta4, corbo::IntegratorExplicitRungeKutta3, corbo::IntegratorExplicitRungeKutta2, and corbo::IntegratorExplicitEuler.
|
overridepure virtual |
Return a newly created shared instance of the implemented class.
Implements corbo::DynamicsEvalInterface.
Implemented in corbo::IntegratorMultiStageScaled, corbo::IntegratorMultiStageFixedStep, corbo::IntegratorAdaptiveStepSize, corbo::IntegratorExplicitRungeKutta7, corbo::IntegratorExplicitRungeKutta6, corbo::IntegratorExplicitRungeKutta5, corbo::IntegratorExplicitRungeKutta4, corbo::IntegratorExplicitRungeKutta3, corbo::IntegratorExplicitRungeKutta2, and corbo::IntegratorExplicitEuler.
|
inlinevirtual |
Allocate memory for a given state dimension.
[in] | state_dim | Expected dimension of the state vector |
Reimplemented in corbo::IntegratorAdaptiveStepSize, corbo::IntegratorExplicitRungeKutta7, corbo::IntegratorExplicitRungeKutta6, corbo::IntegratorExplicitRungeKutta5, corbo::IntegratorExplicitRungeKutta4, corbo::IntegratorExplicitRungeKutta3, and corbo::IntegratorExplicitRungeKutta2.
Definition at line 182 of file integrator_interface.h.
|
inlineoverridevirtual |
Implements corbo::DynamicsEvalInterface.
Definition at line 231 of file integrator_interface.h.
|
pure virtual |
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) |
Implemented in corbo::IntegratorMultiStageScaled, and corbo::IntegratorMultiStageFixedStep.
|
pure virtual |
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) |
Implemented in corbo::IntegratorMultiStageScaled, corbo::IntegratorMultiStageFixedStep, corbo::IntegratorAdaptiveStepSize, corbo::IntegratorExplicitRungeKutta7, corbo::IntegratorExplicitRungeKutta6, corbo::IntegratorExplicitRungeKutta5, corbo::IntegratorExplicitRungeKutta4, corbo::IntegratorExplicitRungeKutta3, corbo::IntegratorExplicitRungeKutta2, and corbo::IntegratorExplicitEuler.