7#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
8#include <pinocchio/multibody/model.hpp>
12template <
typename Scalar>
struct KinodynamicsFwdDataTpl;
28template <
typename _Scalar>
30 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
37 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
38 using Model = pinocchio::ModelTpl<Scalar>;
55 const Manifold &state,
const Model &model,
const Vector3s &gravity,
56 const std::vector<bool> &contact_states,
57 const std::vector<pinocchio::FrameIndex> &contact_ids,
58 const int force_size);
60 void forward(
const ConstVectorRef &x,
const ConstVectorRef &u,
62 void dForward(
const ConstVectorRef &x,
const ConstVectorRef &u,
68template <
typename Scalar>
71 using PinData = pinocchio::DataTpl<Scalar>;
72 using VectorXs =
typename math_types<Scalar>::VectorXs;
73 using Matrix6Xs =
typename math_types<Scalar>::Matrix6Xs;
74 using Matrix3Xs =
typename math_types<Scalar>::Matrix3Xs;
93 Eigen::PartialPivLU<Eigen::Matrix<Scalar, 6, 6>>
PivLU_;
101#include "aligator/modelling/dynamics/kinodynamics-fwd.hxx"
Defines a class representing ODEs.
Data struct for ContinuousDynamicsAbstractTpl.
typename math_types< Scalar >::Matrix6Xs Matrix6Xs
Eigen::Matrix< Scalar, 6, 1 > Vector6s
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
KinodynamicsFwdDataTpl(const KinodynamicsFwdDynamicsTpl< Scalar > *model)
typename math_types< Scalar >::VectorXs VectorXs
pinocchio::DataTpl< Scalar > PinData
Eigen::PartialPivLU< Eigen::Matrix< Scalar, 6, 6 > > PivLU_
typename math_types< Scalar >::Matrix3Xs Matrix3Xs
Eigen::Matrix< Scalar, 6, 6 > Matrix6s
Nonlinear centroidal and full kinematics forward dynamics.
proxsuite::nlp::MultibodyPhaseSpace< Scalar > Manifold
const Manifold & space() const
void dForward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the vector field Jacobians.
std::vector< pinocchio::FrameIndex > contact_ids_
KinodynamicsFwdDynamicsTpl(const Manifold &state, const Model &model, const Vector3s &gravity, const std::vector< bool > &contact_states, const std::vector< pinocchio::FrameIndex > &contact_ids, const int force_size)
pinocchio::ModelTpl< Scalar > Model
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
void forward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the ODE vector field: this returns the value of .
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
std::vector< bool > contact_states_
Base class for ODE dynamics .
const int nu_
Control space dimension.