21template <
typename _Scalar>
33 const Vector3s &gravity,
40 ALIGATOR_DOMAIN_ERROR(
41 fmt::format(
"Contact ids and nk should be the same: now "
43 contact_map.size_, nk_));
47 void evaluate(
const ConstVectorRef &,
const ConstVectorRef &u,
54 return std::make_shared<Data>(
this);
66template <
typename Scalar>
68 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
81#include "aligator/modelling/centroidal/angular-acceleration.txx"
Base definitions for ternary functions.
AngularAccelerationDataTpl(const AngularAccelerationResidualTpl< Scalar > *model)
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
StageFunctionDataTpl< Scalar > Base
This residual returns the angular acceleration of a centroidal model with state , computed from the e...
StageFunctionTpl< Scalar > Base
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
AngularAccelerationResidualTpl(const int ndx, const int nu, const double mass, const Vector3s &gravity, const ContactMap &contact_map, const int force_size)
ContactMapTpl< Scalar > ContactMap
shared_ptr< BaseData > createData() const
Instantiate a Data object.
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &, BaseData &data) const
void evaluate(const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
typename Base::Data BaseData
AngularAccelerationDataTpl< Scalar > Data
StageFunctionDataTpl(const int ndx, const int nu, const int nr)
const int nu
Control dimension.
StageFunctionDataTpl< Scalar > Data
StageFunctionTpl(const int ndx, const int nu, const int nr)