aligator  0.15.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
integrator-euler.hpp
Go to the documentation of this file.
1#pragma once
5
7
8namespace aligator {
9namespace dynamics {
13template <typename _Scalar>
15 using Scalar = _Scalar;
21
24
25 IntegratorEulerTpl(const xyz::polymorphic<ODEType> &cont_dynamics,
26 const Scalar timestep);
27
28 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
30
31 void dForward(const ConstVectorRef &x, const ConstVectorRef &u,
33};
34
35#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
36extern template struct IntegratorEulerTpl<context::Scalar>;
37#endif
38
39} // namespace dynamics
40} // namespace aligator
Base definitions for explicit integrators.
Namespace for modelling system dynamics.
Main package namespace.
Specific data struct for explicit dynamics ExplicitDynamicsModelTpl.
Data struct for ContinuousDynamicsAbstractTpl.
ExplicitIntegratorAbstractTpl(const xyz::polymorphic< ODEType > &cont_dynamics)
void forward(const ConstVectorRef &x, const ConstVectorRef &u, ExplicitDynamicsDataTpl< Scalar > &data) const
IntegratorEulerTpl(const xyz::polymorphic< ODEType > &cont_dynamics, const Scalar timestep)
Scalar timestep_
Integration time step .
ExplicitIntegratorAbstractTpl< Scalar > Base
ContinuousDynamicsDataTpl< Scalar > ODEData
ExplicitIntegratorDataTpl< Scalar > Data
void dForward(const ConstVectorRef &x, const ConstVectorRef &u, ExplicitDynamicsDataTpl< Scalar > &data) const
Base class for ODE dynamics .