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

Results holder struct. More...

#include <aligator/solvers/proxddp/results.hpp>

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

Public Types

using Scalar = _Scalar
 
using Base = ResultsBaseTpl<Scalar>
 
- Public Types inherited from aligator::ResultsBaseTpl< _Scalar >
using Scalar
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 ResultsTpl ()
 
 ResultsTpl (const ResultsTpl &)=delete
 
ResultsTploperator= (const ResultsTpl &)=delete
 
 ResultsTpl (ResultsTpl &&)=default
 
ResultsTploperator= (ResultsTpl &&)=default
 
 ResultsTpl (const TrajOptProblemTpl< Scalar > &problem)
 Create the results struct from a problem (TrajOptProblemTpl) instance.
 
void cycleAppend (const TrajOptProblemTpl< Scalar > &problem, const ConstVectorRef &x0)
 
- Public Member Functions inherited from aligator::ResultsBaseTpl< _Scalar >
 ALIGATOR_DYNAMIC_TYPEDEFS (_Scalar)
 
 ResultsBaseTpl ()
 
bool isInitialized () const
 
decltype(auto) getFeedforward (std::size_t i)
 Get column expression of the primal-dual feedforward gain.
 
decltype(auto) getFeedforward (std::size_t i) const
 Get column expression of the primal-dual feedforward gain.
 
decltype(auto) getFeedback (std::size_t i)
 Get expression of the primal-dual feedback gains.
 
decltype(auto) getFeedback (std::size_t i) const
 Get expression of the primal-dual feedback gains.
 
std::vector< MatrixXs > getCtrlFeedbacks () const
 
std::vector< VectorXs > getCtrlFeedforwards () const
 
void printBase (std::ostream &oss) const
 
virtual ~ResultsBaseTpl ()=default
 

Public Attributes

std::vector< VectorXs > lams
 Problem co-states.
 
std::vector< VectorXs > vs
 Path constraint multipliers.
 
std::size_t al_iter = 0
 Proximal/AL iteration count.
 
bool conv
 
std::vector< MatrixXs > gains_
 Riccati gains.
 
std::size_t num_iters
 
std::vector< VectorXs > us
 Controls.
 
std::vector< VectorXs > xs
 States.
 
- Public Attributes inherited from aligator::ResultsBaseTpl< _Scalar >
std::size_t num_iters
 
bool conv
 
_Scalar traj_cost_
 
_Scalar merit_value_
 
_Scalar prim_infeas
 Overall primal infeasibility measure/constraint violation.
 
_Scalar dual_infeas
 Overall dual infeasibility measure.
 
std::vector< MatrixXs > gains_
 Riccati gains.
 
std::vector< VectorXs > xs
 States.
 
std::vector< VectorXs > us
 Controls.
 

Additional Inherited Members

- Protected Attributes inherited from aligator::ResultsBaseTpl< _Scalar >
bool m_isInitialized
 

Detailed Description

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

Results holder struct.

Definition at line 11 of file results.hpp.

Member Typedef Documentation

◆ Scalar

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

Definition at line 12 of file results.hpp.

◆ Base

template<typename _Scalar >
using aligator::ResultsTpl< _Scalar >::Base = ResultsBaseTpl<Scalar>

Definition at line 14 of file results.hpp.

Constructor & Destructor Documentation

◆ ResultsTpl() [1/4]

template<typename _Scalar >
aligator::ResultsTpl< _Scalar >::ResultsTpl ( )
inline

Definition at line 28 of file results.hpp.

◆ ResultsTpl() [2/4]

template<typename _Scalar >
aligator::ResultsTpl< _Scalar >::ResultsTpl ( const ResultsTpl< _Scalar > & )
delete

◆ ResultsTpl() [3/4]

template<typename _Scalar >
aligator::ResultsTpl< _Scalar >::ResultsTpl ( ResultsTpl< _Scalar > && )
default

◆ ResultsTpl() [4/4]

template<typename _Scalar >
aligator::ResultsTpl< _Scalar >::ResultsTpl ( const TrajOptProblemTpl< Scalar > & problem)
explicit

Create the results struct from a problem (TrajOptProblemTpl) instance.

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

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

◆ operator=() [1/2]

template<typename _Scalar >
ResultsTpl & aligator::ResultsTpl< _Scalar >::operator= ( const ResultsTpl< _Scalar > & )
delete

◆ operator=() [2/2]

template<typename _Scalar >
ResultsTpl & aligator::ResultsTpl< _Scalar >::operator= ( ResultsTpl< _Scalar > && )
default

◆ cycleAppend()

template<typename _Scalar >
void aligator::ResultsTpl< _Scalar >::cycleAppend ( const TrajOptProblemTpl< Scalar > & problem,
const ConstVectorRef & x0 )

Member Data Documentation

◆ lams

template<typename _Scalar >
std::vector<VectorXs> aligator::ResultsTpl< _Scalar >::lams

Problem co-states.

Definition at line 22 of file results.hpp.

◆ vs

template<typename _Scalar >
std::vector<VectorXs> aligator::ResultsTpl< _Scalar >::vs

Path constraint multipliers.

Definition at line 24 of file results.hpp.

◆ al_iter

template<typename _Scalar >
std::size_t aligator::ResultsTpl< _Scalar >::al_iter = 0

Proximal/AL iteration count.

Definition at line 26 of file results.hpp.

◆ conv

template<typename _Scalar >
bool aligator::ResultsBaseTpl< Scalar >::conv

Definition at line 19 of file results-base.hpp.

◆ gains_

template<typename _Scalar >
std::vector<MatrixXs> aligator::ResultsBaseTpl< Scalar >::gains_

Riccati gains.

Definition at line 29 of file results-base.hpp.

◆ num_iters

template<typename _Scalar >
std::size_t aligator::ResultsBaseTpl< Scalar >::num_iters

Definition at line 18 of file results-base.hpp.

◆ us

template<typename _Scalar >
std::vector<VectorXs> aligator::ResultsBaseTpl< Scalar >::us

Controls.

Definition at line 33 of file results-base.hpp.

◆ xs

template<typename _Scalar >
std::vector<VectorXs> aligator::ResultsBaseTpl< Scalar >::xs

States.

Definition at line 31 of file results-base.hpp.


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