|
aligator
0.16.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
|
This residual returns the derivative of centroidal momentum for a kinodynamics model. More...
#include <aligator/modelling/multibody/multibody-friction-cone.hpp>
Public Types | |
| using | Scalar = _Scalar |
| using | Base = StageFunctionTpl<Scalar> |
| using | BaseData = typename Base::Data |
| using | PinModel = pinocchio::ModelTpl<Scalar> |
| using | SE3 = pinocchio::SE3Tpl<Scalar> |
| using | Data = MultibodyFrictionConeDataTpl<Scalar> |
| using | RigidConstraintModelVector |
| using | RigidConstraintDataVector |
| using | ProxSettings = pinocchio::ProximalSettingsTpl<Scalar> |
Public Types inherited from aligator::StageFunctionTpl< _Scalar > | |
| using | Scalar = _Scalar |
| using | Data = StageFunctionDataTpl<Scalar> |
Public Member Functions | |
| ALIGATOR_DYNAMIC_TYPEDEFS (Scalar) | |
| MultibodyFrictionConeResidualTpl (const int ndx, const PinModel &model, const MatrixXs &actuation, const RigidConstraintModelVector &constraint_models, const ProxSettings &prox_settings, std::string_view contact_name, const double mu) | |
| void | evaluate (const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const |
| void | computeJacobians (const ConstVectorRef &, const ConstVectorRef &, BaseData &data) const |
| shared_ptr< BaseData > | createData () const |
| Instantiate a Data object. | |
Public Member Functions inherited from aligator::StageFunctionTpl< _Scalar > | |
| ALIGATOR_DYNAMIC_TYPEDEFS (Scalar) | |
| StageFunctionTpl (const int ndx, const int nu, const int nr) | |
| virtual void | evaluate (const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const =0 |
| Evaluate the function. | |
| virtual void | computeJacobians (const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const =0 |
| Compute Jacobians of this function. | |
| virtual void | computeVectorHessianProducts (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &lbda, Data &data) const |
| Compute the vector-hessian products of this function. | |
| virtual | ~StageFunctionTpl ()=default |
Public Attributes | |
| PinModel | pin_model_ |
| MatrixXs | actuation_matrix_ |
| RigidConstraintModelVector | constraint_models_ |
| ProxSettings | prox_settings_ |
| double | mu_ |
| int | contact_id_ |
Public Attributes inherited from aligator::StageFunctionTpl< _Scalar > | |
| const int | ndx1 |
| Current state dimension. | |
| const int | nu |
| Control dimension. | |
| const int | nr |
| Function codimension. | |
This residual returns the derivative of centroidal momentum for a kinodynamics model.
Definition at line 19 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::Scalar = _Scalar |
Definition at line 21 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::Base = StageFunctionTpl<Scalar> |
Definition at line 23 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::BaseData = typename Base::Data |
Definition at line 24 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::PinModel = pinocchio::ModelTpl<Scalar> |
Definition at line 25 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::SE3 = pinocchio::SE3Tpl<Scalar> |
Definition at line 26 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::Data = MultibodyFrictionConeDataTpl<Scalar> |
Definition at line 27 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::RigidConstraintModelVector |
Definition at line 28 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::RigidConstraintDataVector |
Definition at line 30 of file multibody-friction-cone.hpp.
| using aligator::MultibodyFrictionConeResidualTpl< _Scalar >::ProxSettings = pinocchio::ProximalSettingsTpl<Scalar> |
Definition at line 32 of file multibody-friction-cone.hpp.
|
inline |
Definition at line 41 of file multibody-friction-cone.hpp.
| aligator::MultibodyFrictionConeResidualTpl< _Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS | ( | Scalar | ) |
| void aligator::MultibodyFrictionConeResidualTpl< _Scalar >::evaluate | ( | const ConstVectorRef & | x, |
| const ConstVectorRef & | u, | ||
| BaseData & | data ) const |
| void aligator::MultibodyFrictionConeResidualTpl< _Scalar >::computeJacobians | ( | const ConstVectorRef & | , |
| const ConstVectorRef & | , | ||
| BaseData & | data ) const |
|
inlinevirtual |
Instantiate a Data object.
Reimplemented from aligator::StageFunctionTpl< _Scalar >.
Definition at line 75 of file multibody-friction-cone.hpp.
| PinModel aligator::MultibodyFrictionConeResidualTpl< _Scalar >::pin_model_ |
Definition at line 34 of file multibody-friction-cone.hpp.
| MatrixXs aligator::MultibodyFrictionConeResidualTpl< _Scalar >::actuation_matrix_ |
Definition at line 35 of file multibody-friction-cone.hpp.
| RigidConstraintModelVector aligator::MultibodyFrictionConeResidualTpl< _Scalar >::constraint_models_ |
Definition at line 36 of file multibody-friction-cone.hpp.
| ProxSettings aligator::MultibodyFrictionConeResidualTpl< _Scalar >::prox_settings_ |
Definition at line 37 of file multibody-friction-cone.hpp.
| double aligator::MultibodyFrictionConeResidualTpl< _Scalar >::mu_ |
Definition at line 38 of file multibody-friction-cone.hpp.
| int aligator::MultibodyFrictionConeResidualTpl< _Scalar >::contact_id_ |
Definition at line 39 of file multibody-friction-cone.hpp.