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

Class representing ternary functions \(f(x,u,x')\). More...

#include <aligator/core/function-abstract.hpp>

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

Public Types

using Scalar = _Scalar
 
using Data = StageFunctionDataTpl<Scalar>
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 StageFunctionTpl (const int ndx1, const int nu, const int ndx2, const int nr)
 
 StageFunctionTpl (const int ndx, const int nu, const int nr)
 Constructor where ndx2 = ndx1.
 
virtual void evaluate (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const =0
 Evaluate the function.
 
virtual void computeJacobians (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const =0
 Compute Jacobians of this function.
 
virtual void computeVectorHessianProducts (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, const ConstVectorRef &lbda, Data &data) const
 Compute the vector-hessian products of this function.
 
virtual ~StageFunctionTpl ()=default
 
virtual shared_ptr< DatacreateData () const
 Instantiate a Data object.
 

Public Attributes

const int ndx1
 Current state dimension.
 
const int nu
 Control dimension.
 
const int ndx2
 Next state dimension.
 
const int nr
 Function codimension.
 

Detailed Description

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

Class representing ternary functions \(f(x,u,x')\).

Definition at line 16 of file function-abstract.hpp.

Member Typedef Documentation

◆ Scalar

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

Definition at line 19 of file function-abstract.hpp.

◆ Data

template<typename _Scalar >
using aligator::StageFunctionTpl< _Scalar >::Data = StageFunctionDataTpl<Scalar>

Definition at line 21 of file function-abstract.hpp.

Constructor & Destructor Documentation

◆ StageFunctionTpl() [1/2]

template<typename _Scalar >
aligator::StageFunctionTpl< _Scalar >::StageFunctionTpl ( const int ndx1,
const int nu,
const int ndx2,
const int nr )

◆ StageFunctionTpl() [2/2]

template<typename _Scalar >
aligator::StageFunctionTpl< _Scalar >::StageFunctionTpl ( const int ndx,
const int nu,
const int nr )

Constructor where ndx2 = ndx1.

◆ ~StageFunctionTpl()

template<typename _Scalar >
virtual aligator::StageFunctionTpl< _Scalar >::~StageFunctionTpl ( )
virtualdefault

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

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

◆ evaluate()

template<typename _Scalar >
virtual void aligator::StageFunctionTpl< _Scalar >::evaluate ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
Data & data ) const
pure virtual

◆ computeJacobians()

template<typename _Scalar >
virtual void aligator::StageFunctionTpl< _Scalar >::computeJacobians ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
Data & data ) const
pure virtual

Compute Jacobians of this function.

This computes the Jacobians \( (\frac{\partial f}{\partial x}, \frac{\partial f}{\partial u}, \frac{\partial f}{\partial x'}) \)

Parameters
xCurrent state.
uControls.
yNext state.
dataData holding struct.

Implemented in aligator::LinearFunctionTpl< Scalar >, aligator::detail::StateOrControlErrorResidual< _Scalar, arg >, aligator::detail::StateOrControlErrorResidual< Scalar, 0 >, aligator::detail::StateOrControlErrorResidual< Scalar, 1 >, aligator::UnaryFunctionTpl< _Scalar >, aligator::UnaryFunctionTpl< Scalar >, aligator::LinearFunctionCompositionTpl< _Scalar >, and aligator::FunctionSliceXprTpl< Scalar, Base >.

◆ computeVectorHessianProducts()

template<typename _Scalar >
virtual void aligator::StageFunctionTpl< _Scalar >::computeVectorHessianProducts ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
const ConstVectorRef & lbda,
Data & data ) const
virtual

Compute the vector-hessian products of this function.

Parameters
xCurrent state.
uControls.
yNext state.
lbdaMultiplier estimate.
dataData holding struct.

Reimplemented in aligator::UnaryFunctionTpl< _Scalar >, aligator::UnaryFunctionTpl< Scalar >, and aligator::FunctionSliceXprTpl< Scalar, Base >.

◆ createData()

template<typename _Scalar >
virtual shared_ptr< Data > aligator::StageFunctionTpl< _Scalar >::createData ( ) const
virtual

Instantiate a Data object.

Reimplemented in aligator::ExplicitDynamicsModelTpl< _Scalar >, aligator::AngularAccelerationResidualTpl< _Scalar >, aligator::AngularMomentumResidualTpl< _Scalar >, aligator::CentroidalAccelerationResidualTpl< _Scalar >, aligator::CentroidalCoMResidualTpl< _Scalar >, aligator::CentroidalWrapperResidualTpl< _Scalar >, aligator::FrictionConeResidualTpl< _Scalar >, aligator::LinearMomentumResidualTpl< _Scalar >, aligator::WrenchConeResidualTpl< _Scalar >, aligator::dynamics::IntegratorAbstractTpl< _Scalar >, aligator::dynamics::ExplicitIntegratorAbstractTpl< _Scalar >, aligator::dynamics::IntegratorMidpointTpl< _Scalar >, aligator::dynamics::IntegratorRK2Tpl< _Scalar >, aligator::dynamics::IntegratorSemiImplEulerTpl< _Scalar >, aligator::dynamics::LinearDiscreteDynamicsTpl< _Scalar >, aligator::detail::linear_func_composition_impl< StageFunctionTpl< _Scalar > >, aligator::detail::linear_func_composition_impl< UnaryFunctionTpl< _Scalar > >, aligator::LinearFunctionCompositionTpl< _Scalar >, aligator::LinearUnaryFunctionCompositionTpl< _Scalar >, aligator::LinearFunctionTpl< Scalar >, aligator::CenterOfMassTranslationResidualTpl< _Scalar >, aligator::CenterOfMassVelocityResidualTpl< _Scalar >, aligator::CentroidalMomentumDerivativeResidualTpl< _Scalar >, aligator::CentroidalMomentumResidualTpl< _Scalar >, aligator::FlyHighResidualTpl< _Scalar >, aligator::FramePlacementResidualTpl< _Scalar >, aligator::FrameTranslationResidualTpl< _Scalar >, aligator::FrameVelocityResidualTpl< _Scalar >, aligator::DirectSumExplicitDynamicsTpl< _Scalar >, aligator::FunctionSliceXprTpl< Scalar, Base >, and aligator::FunctionSliceXprTpl< Scalar, UnaryFunctionTpl< Scalar > >.

Member Data Documentation

◆ ndx1

template<typename _Scalar >
const int aligator::StageFunctionTpl< _Scalar >::ndx1

Current state dimension.

Definition at line 24 of file function-abstract.hpp.

◆ nu

template<typename _Scalar >
const int aligator::StageFunctionTpl< _Scalar >::nu

Control dimension.

Definition at line 26 of file function-abstract.hpp.

◆ ndx2

template<typename _Scalar >
const int aligator::StageFunctionTpl< _Scalar >::ndx2

Next state dimension.

Definition at line 28 of file function-abstract.hpp.

◆ nr

template<typename _Scalar >
const int aligator::StageFunctionTpl< _Scalar >::nr

Function codimension.

Definition at line 30 of file function-abstract.hpp.


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