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