aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
aligator::CentroidalFrictionConeResidualTpl< _Scalar > Struct Template Reference

#include <aligator/modelling/centroidal/centroidal-friction-cone.hpp>

Inheritance diagram for aligator::CentroidalFrictionConeResidualTpl< _Scalar >:
[legend]
Collaboration diagram for aligator::CentroidalFrictionConeResidualTpl< _Scalar >:
[legend]

Public Types

using Scalar = _Scalar
 
using Base = StageFunctionTpl<Scalar>
 
using BaseData = typename Base::Data
 
using Data = CentroidalFrictionConeDataTpl<Scalar>
 
- Public Types inherited from aligator::StageFunctionTpl< _Scalar >
using Scalar
 
using Data
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 CentroidalFrictionConeResidualTpl (const int ndx, const int nu, const int k, const double mu, const double epsilon)
 
void evaluate (const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
 
void computeJacobians (const ConstVectorRef &, const ConstVectorRef &u, BaseData &data) const
 
shared_ptr< BaseDatacreateData () const
 Instantiate a Data object.
 
- Public Member Functions inherited from aligator::StageFunctionTpl< _Scalar >
 ALIGATOR_DYNAMIC_TYPEDEFS (_Scalar)
 
 StageFunctionTpl (const int ndx, const int nu, const int nr)
 
virtual void evaluate (const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const=0
 Evaluate the function.
 
virtual void computeJacobians (const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const=0
 Compute Jacobians of this function.
 
virtual void computeVectorHessianProducts (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &lbda, Data &data) const
 Compute the vector-hessian products of this function.
 
virtual ~StageFunctionTpl ()=default
 

Protected Attributes

int k_
 
double mu2_
 
double epsilon_
 

Additional Inherited Members

- Public Attributes inherited from aligator::StageFunctionTpl< _Scalar >
const int ndx1
 Current state dimension.
 
const int nu
 Control dimension.
 
const int nr
 Function codimension.
 

Detailed Description

template<typename _Scalar>
struct aligator::CentroidalFrictionConeResidualTpl< _Scalar >

Definition at line 22 of file centroidal-friction-cone.hpp.

Member Typedef Documentation

◆ Scalar

template<typename _Scalar >
using aligator::CentroidalFrictionConeResidualTpl< _Scalar >::Scalar = _Scalar

Definition at line 25 of file centroidal-friction-cone.hpp.

◆ Base

template<typename _Scalar >
using aligator::CentroidalFrictionConeResidualTpl< _Scalar >::Base = StageFunctionTpl<Scalar>

Definition at line 27 of file centroidal-friction-cone.hpp.

◆ BaseData

template<typename _Scalar >
using aligator::CentroidalFrictionConeResidualTpl< _Scalar >::BaseData = typename Base::Data

Definition at line 28 of file centroidal-friction-cone.hpp.

◆ Data

template<typename _Scalar >
using aligator::CentroidalFrictionConeResidualTpl< _Scalar >::Data = CentroidalFrictionConeDataTpl<Scalar>

Definition at line 29 of file centroidal-friction-cone.hpp.

Constructor & Destructor Documentation

◆ CentroidalFrictionConeResidualTpl()

template<typename _Scalar >
aligator::CentroidalFrictionConeResidualTpl< _Scalar >::CentroidalFrictionConeResidualTpl ( const int ndx,
const int nu,
const int k,
const double mu,
const double epsilon )
inline

Definition at line 31 of file centroidal-friction-cone.hpp.

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

template<typename _Scalar >
aligator::CentroidalFrictionConeResidualTpl< _Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS ( Scalar )

◆ evaluate()

template<typename _Scalar >
void aligator::CentroidalFrictionConeResidualTpl< _Scalar >::evaluate ( const ConstVectorRef & ,
const ConstVectorRef & u,
BaseData & data ) const

◆ computeJacobians()

template<typename _Scalar >
void aligator::CentroidalFrictionConeResidualTpl< _Scalar >::computeJacobians ( const ConstVectorRef & ,
const ConstVectorRef & u,
BaseData & data ) const

◆ createData()

template<typename _Scalar >
shared_ptr< BaseData > aligator::CentroidalFrictionConeResidualTpl< _Scalar >::createData ( ) const
inlinevirtual

Instantiate a Data object.

Reimplemented from aligator::StageFunctionTpl< _Scalar >.

Definition at line 41 of file centroidal-friction-cone.hpp.

Member Data Documentation

◆ k_

template<typename _Scalar >
int aligator::CentroidalFrictionConeResidualTpl< _Scalar >::k_
protected

Definition at line 46 of file centroidal-friction-cone.hpp.

◆ mu2_

template<typename _Scalar >
double aligator::CentroidalFrictionConeResidualTpl< _Scalar >::mu2_
protected

Definition at line 47 of file centroidal-friction-cone.hpp.

◆ epsilon_

template<typename _Scalar >
double aligator::CentroidalFrictionConeResidualTpl< _Scalar >::epsilon_
protected

Definition at line 48 of file centroidal-friction-cone.hpp.


The documentation for this struct was generated from the following file: