aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
multibody-constraint-fwd.hpp
Go to the documentation of this file.
1
2#pragma once
3
5
6#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
7#include <pinocchio/multibody/data.hpp>
8
9#include <pinocchio/algorithm/proximal.hpp>
10
11namespace aligator {
12namespace dynamics {
13template <typename Scalar> struct MultibodyConstraintFwdDataTpl;
14
19template <typename _Scalar>
21 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
22 using Scalar = _Scalar;
28#pragma GCC diagnostic push
29#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
30 using RigidConstraintModelVector = PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(
31 pinocchio::RigidConstraintModelTpl<Scalar>);
33 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintData);
34#pragma GCC diagnostic pop
35 using ProxSettings = pinocchio::ProximalSettingsTpl<Scalar>;
36 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
37
42
43 const Manifold &space() const { return space_; }
44 int ntau() const { return space_.getModel().nv; }
45
47 const Manifold &state, const MatrixXs &actuation,
48 const RigidConstraintModelVector &constraint_models,
49 const ProxSettings &prox_settings);
50
51 virtual void forward(const ConstVectorRef &x, const ConstVectorRef &u,
52 BaseData &data) const;
53 virtual void dForward(const ConstVectorRef &x, const ConstVectorRef &u,
54 BaseData &data) const;
55
56 shared_ptr<ContDataAbstract> createData() const;
57};
58
59template <typename Scalar>
62 using VectorXs = typename math_types<Scalar>::VectorXs;
63 using MatrixXs = typename math_types<Scalar>::MatrixXs;
64 using PinDataType = pinocchio::DataTpl<Scalar>;
65#pragma GCC diagnostic push
66#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
67 using RigidConstraintData = pinocchio::RigidConstraintDataTpl<Scalar>;
68#pragma GCC diagnostic pop
70 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData);
71
76 pinocchio::ProximalSettingsTpl<Scalar> settings;
81};
82
83} // namespace dynamics
84} // namespace aligator
85
86#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
87#include "aligator/modelling/dynamics/multibody-constraint-fwd.txx"
88#endif
Main package namespace.
Defines a class representing ODEs.
Data struct for ContinuousDynamicsAbstractTpl.
Definition fwd.hpp:15
pinocchio::ProximalSettingsTpl< Scalar > settings
PinDataType pin_data_
shared_ptr to the underlying pinocchio::DataTpl object.
pinocchio::RigidConstraintDataTpl< Scalar > RigidConstraintData
MultibodyConstraintFwdDataTpl(const MultibodyConstraintFwdDynamicsTpl< Scalar > &cont_dyn)
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) RigidConstraintDataVector
Constraint multibody forward dynamics, using Pinocchio.
MultibodyConstraintFwdDynamicsTpl(const Manifold &state, const MatrixXs &actuation, const RigidConstraintModelVector &constraint_models, const ProxSettings &prox_settings)
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
virtual void forward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the ODE vector field: this returns the value of .
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR( pinocchio::RigidConstraintModelTpl< Scalar >) RigidConstraintModelVector
virtual void dForward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the vector field Jacobians.
proxsuite::nlp::MultibodyPhaseSpace< Scalar > Manifold
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintData) RigidConstraintDataVector
Base class for ODE dynamics .