aligator  0.12.0
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]

Public Types

using Scalar = _Scalar
 
using Data = StageFunctionDataTpl<Scalar>
 

Public Member Functions

 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
 
virtual shared_ptr< DatacreateData () const
 Instantiate a Data object.
 

Public Attributes

const int ndx1
 Current state dimension.
 
const int nu
 Control 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 12 of file function-abstract.hpp.

Member Typedef Documentation

◆ Scalar

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

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

◆ Data

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

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

Constructor & Destructor Documentation

◆ StageFunctionTpl()

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

◆ ~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()

◆ computeJacobians()

◆ computeVectorHessianProducts()

template<typename _Scalar>
virtual void aligator::StageFunctionTpl< _Scalar >::computeVectorHessianProducts ( const ConstVectorRef & x,
const ConstVectorRef & u,
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::FunctionSliceXprTpl< Scalar, StageFunctionTpl< Scalar > >, aligator::python::PyStageFunction< FunctionBase >, aligator::UnaryFunctionTpl< _Scalar >, aligator::UnaryFunctionTpl< Scalar >, and aligator::UnaryFunctionTpl< Scalar >.

◆ createData()

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

Instantiate a Data object.

Reimplemented in aligator::AngularAccelerationResidualTpl< _Scalar >, aligator::AngularMomentumResidualTpl< _Scalar >, aligator::autodiff::FiniteDifferenceHelper< _Scalar >, aligator::CenterOfMassTranslationResidualTpl< _Scalar >, aligator::CenterOfMassVelocityResidualTpl< _Scalar >, aligator::CentroidalAccelerationResidualTpl< _Scalar >, aligator::CentroidalCoMResidualTpl< _Scalar >, aligator::CentroidalFrictionConeResidualTpl< _Scalar >, aligator::CentroidalMomentumDerivativeResidualTpl< _Scalar >, aligator::CentroidalMomentumResidualTpl< _Scalar >, aligator::CentroidalWrapperResidualTpl< _Scalar >, aligator::CentroidalWrenchConeResidualTpl< _Scalar >, aligator::DCMPositionResidualTpl< _Scalar >, aligator::detail::linear_func_composition_impl< StageFunctionTpl< _Scalar > >, aligator::detail::linear_func_composition_impl< StageFunctionTpl< Scalar > >, aligator::detail::linear_func_composition_impl< StageFunctionTpl< Scalar > >, aligator::detail::linear_func_composition_impl< UnaryFunctionTpl< _Scalar > >, aligator::FrameCollisionResidualTpl< _Scalar >, aligator::FramePlacementResidualTpl< _Scalar >, aligator::FrameTranslationResidualTpl< _Scalar >, aligator::FrameVelocityResidualTpl< _Scalar >, aligator::FunctionSliceXprTpl< Scalar, StageFunctionTpl< Scalar > >, aligator::FunctionSliceXprTpl< Scalar, UnaryFunctionTpl< Scalar > >, aligator::GravityCompensationResidualTpl< _Scalar >, aligator::LinearFunctionCompositionTpl< _Scalar >, aligator::LinearFunctionTpl< Scalar >, aligator::LinearMomentumResidualTpl< _Scalar >, aligator::LinearUnaryFunctionCompositionTpl< _Scalar >, aligator::python::PyStageFunction< FunctionBase >, and aligator::python::PyUnaryFunction< UFunction >.

Member Data Documentation

◆ ndx1

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

Current state dimension.

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

◆ nu

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

Control dimension.

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

◆ nr

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

Function codimension.

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


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