aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
centroidal-friction-cone.hpp
Go to the documentation of this file.
1#pragma once
2
4
5namespace aligator {
6
19template <typename Scalar> struct CentroidalFrictionConeDataTpl;
20
21template <typename _Scalar>
23
24public:
25 using Scalar = _Scalar;
28 using BaseData = typename Base::Data;
30
31 CentroidalFrictionConeResidualTpl(const int ndx, const int nu, const int k,
32 const double mu, const double epsilon)
33 : Base(ndx, nu, 2), k_(k), mu2_(mu * mu), epsilon_(epsilon) {}
34
35 void evaluate(const ConstVectorRef &, const ConstVectorRef &u,
36 BaseData &data) const;
37
38 void computeJacobians(const ConstVectorRef &, const ConstVectorRef &u,
39 BaseData &data) const;
40
41 shared_ptr<BaseData> createData() const {
42 return std::make_shared<Data>(this);
43 }
44
45protected:
46 int k_;
47 double mu2_;
48 double epsilon_;
49};
50
51template <typename Scalar>
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55 using Matrix23s = Eigen::Matrix<Scalar, 2, 3>;
56
58
61};
62
63} // namespace aligator
64
65#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
66#include "aligator/modelling/centroidal/centroidal-friction-cone.txx"
67#endif
Base definitions for ternary functions.
Main package namespace.
This residual implements the "ice cream" friction cone for a centroidal model with state .
CentroidalFrictionConeDataTpl(const CentroidalFrictionConeResidualTpl< Scalar > *model)
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
void evaluate(const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
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.
Definition fwd.hpp:59
Class representing ternary functions .
Definition fwd.hpp:53
StageFunctionDataTpl< Scalar > Data