7template <
typename Scalar>
struct CentroidalCoMDataTpl;
9template <
typename _Scalar>
30 return std::make_shared<Data>(
this);
37template <
typename Scalar>
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
48#include "aligator/modelling/centroidal/centroidal-translation.txx"
CentroidalCoMDataTpl(const CentroidalCoMResidualTpl< Scalar > *model)
CentroidalCoMResidualTpl(const int ndx, const int nu, const Vector3s &p_ref)
typename Base::Data BaseData
shared_ptr< BaseData > createData() const
Instantiate a Data object.
ALIGATOR_UNARY_FUNCTION_INTERFACE(Scalar)
void evaluate(const ConstVectorRef &x, BaseData &data) const
void computeJacobians(const ConstVectorRef &, BaseData &data) const
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
void setReference(const Eigen::Ref< const Vector3s > &p_new)
const Vector3s & getReference() const
Base struct for function data.
StageFunctionDataTpl< _Scalar > Data
Represents unary functions of the form , with no control (or next-state) arguments.