19template <
typename Scalar>
struct CentroidalFrictionConeDataTpl;
21template <
typename _Scalar>
32 const double mu,
const double epsilon)
35 void evaluate(
const ConstVectorRef &,
const ConstVectorRef &u,
42 return std::make_shared<Data>(
this);
51template <
typename Scalar>
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
65#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
66#include "aligator/modelling/centroidal/centroidal-friction-cone.txx"
Base definitions for ternary functions.
This residual implements the "ice cream" friction cone for a centroidal model with state .
CentroidalFrictionConeDataTpl(const CentroidalFrictionConeResidualTpl< Scalar > *model)
Eigen::Matrix< Scalar, 2, 3 > Matrix23s
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
void evaluate(const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
typename Base::Data BaseData
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
CentroidalFrictionConeResidualTpl(const int ndx, const int nu, const int k, const double mu, const double epsilon)
shared_ptr< BaseData > createData() const
Instantiate a Data object.
Base struct for function data.
Class representing ternary functions .
StageFunctionDataTpl< Scalar > Data