8template <
typename Scalar>
struct CentroidalAccelerationDataTpl;
21template <
typename _Scalar>
33 const double mass,
const Vector3s &gravity,
41 fmt::format(
"Contact ids and nk should be the same: now "
47 void evaluate(
const ConstVectorRef &,
const ConstVectorRef &u,
54 return std::make_shared<Data>(
this);
66template <
typename Scalar>
68 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
77#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
78#include "aligator/modelling/centroidal/centroidal-acceleration.txx"
#define ALIGATOR_DOMAIN_ERROR(msg)
Base definitions for ternary functions.
CentroidalAccelerationDataTpl(const CentroidalAccelerationResidualTpl< Scalar > *model)
This residual returns the linear acceleration of a centroidal model with state , computed from the ex...
CentroidalAccelerationResidualTpl(const int ndx, const int nu, const double mass, const Vector3s &gravity, const ContactMap &contact_map, const int force_size)
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
shared_ptr< BaseData > createData() const
Instantiate a Data object.
typename Base::Data BaseData
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &, BaseData &data) const
void evaluate(const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
Base struct for function data.
Class representing ternary functions .
StageFunctionDataTpl< Scalar > Data