Public Types | Public Member Functions | Protected Attributes | List of all members
corbo::QuadraticFinalStateCost Class Reference

#include <final_state_cost.h>

Inheritance diagram for corbo::QuadraticFinalStateCost:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< QuadraticFinalStateCost >
 
- Public Types inherited from corbo::BaseQuadraticFinalStateCost
using ConstPtr = std::shared_ptr< const BaseQuadraticFinalStateCost >
 
using Ptr = std::shared_ptr< BaseQuadraticFinalStateCost >
 
- Public Types inherited from corbo::FinalStageCost
using ConstPtr = std::shared_ptr< const FinalStageCost >
 
using Ptr = std::shared_ptr< FinalStageCost >
 
- Public Types inherited from corbo::StageFunction
using ConstPtr = std::shared_ptr< const StageFunction >
 
using Ptr = std::shared_ptr< StageFunction >
 

Public Member Functions

bool checkParameters (int state_dim, int control_dim, std::stringstream *issues) const override
 
void computeNonIntegralStateTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
 
FinalStageCost::Ptr getInstance () const override
 Return a newly created shared instance of the implemented class. More...
 
int getNonIntegralStateTermDimension (int k) const override
 
const Eigen::MatrixXd & getWeightQf () const override
 
bool isLsqFormNonIntegralStateTerm (int k) const override
 
 QuadraticFinalStateCost ()
 
 QuadraticFinalStateCost (const Eigen::Ref< const Eigen::MatrixXd > &Qf, bool lsq_form)
 
void setLsqForm (bool lsq_form)
 
bool setWeightQf (const Eigen::Ref< const Eigen::MatrixXd > &Qf)
 
bool setWeightQf (const Eigen::DiagonalMatrix< double, -1 > &Qf)
 
bool update (int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *grid) override
 
- Public Member Functions inherited from corbo::FinalStageCost
bool hasIntegralTerms (int k) const final
 
bool hasNonIntegralTerms (int k) const final
 
- Public Member Functions inherited from corbo::StageFunction
virtual void computeConcatenatedNonIntegralStateControlTerms (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, double dt_k, Eigen::Ref< Eigen::VectorXd > cost, bool lsq_mode=false) const
 
virtual void computeConcatenatedNonIntegralStateTerms (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, double dt_k, Eigen::Ref< Eigen::VectorXd > cost, bool lsq_mode=false) const
 
virtual void computeNonIntegralStateDtTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, double dt_k, Eigen::Ref< Eigen::VectorXd > cost) const
 computeNonIntegralStateDtTerm: warning: currently only supported for full discretization More...
 
virtual int getConcatenatedNonIntegralStateControlTermDimension (int k, bool lsq_mode=false) const
 
virtual int getConcatenatedNonIntegralStateTermDimension (int k, bool lsq_mode=false) const
 
virtual int getNonIntegralStateDtTermDimension (int k) const
 
virtual bool isLinearNonIntegralControlTerm (int k) const
 
virtual bool isLinearNonIntegralDtTerm (int k) const
 
virtual bool isLinearNonIntegralStateTerm (int k) const
 
virtual bool isLsqFormNonIntegralControlTerm (int k) const
 
virtual bool isLsqFormNonIntegralDtTerm (int k) const
 
virtual ~StageFunction ()=default
 Default destructor. More...
 

Protected Attributes

bool _diagonal_mode = false
 
bool _diagonal_mode_intentionally = false
 
bool _lsq_form = true
 
Eigen::MatrixXd _Qf
 
Eigen::DiagonalMatrix< double, -1 > _Qf_diag
 
Eigen::DiagonalMatrix< double, -1 > _Qf_diag_sqrt
 
Eigen::MatrixXd _Qf_sqrt
 
const ReferenceTrajectoryInterface_x_ref = nullptr
 
bool _zero_x_ref = false
 

Detailed Description

Definition at line 47 of file final_state_cost.h.

Member Typedef Documentation

◆ Ptr

Definition at line 50 of file final_state_cost.h.

Constructor & Destructor Documentation

◆ QuadraticFinalStateCost() [1/2]

corbo::QuadraticFinalStateCost::QuadraticFinalStateCost ( )
inline

Definition at line 52 of file final_state_cost.h.

◆ QuadraticFinalStateCost() [2/2]

corbo::QuadraticFinalStateCost::QuadraticFinalStateCost ( const Eigen::Ref< const Eigen::MatrixXd > &  Qf,
bool  lsq_form 
)
inline

Definition at line 54 of file final_state_cost.h.

Member Function Documentation

◆ checkParameters()

bool corbo::QuadraticFinalStateCost::checkParameters ( int  state_dim,
int  control_dim,
std::stringstream *  issues 
) const
overridevirtual

Reimplemented from corbo::StageFunction.

Definition at line 114 of file final_state_cost.cpp.

◆ computeNonIntegralStateTerm()

void corbo::QuadraticFinalStateCost::computeNonIntegralStateTerm ( int  k,
const Eigen::Ref< const Eigen::VectorXd > &  x_k,
Eigen::Ref< Eigen::VectorXd >  cost 
) const
overridevirtual

Implements corbo::FinalStageCost.

Definition at line 72 of file final_state_cost.cpp.

◆ getInstance()

FinalStageCost::Ptr corbo::QuadraticFinalStateCost::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Implements corbo::FinalStageCost.

Definition at line 56 of file final_state_cost.h.

◆ getNonIntegralStateTermDimension()

int corbo::QuadraticFinalStateCost::getNonIntegralStateTermDimension ( int  k) const
inlineoverridevirtual

Implements corbo::FinalStageCost.

Definition at line 58 of file final_state_cost.h.

◆ getWeightQf()

const Eigen::MatrixXd& corbo::QuadraticFinalStateCost::getWeightQf ( ) const
inlineoverridevirtual

Implements corbo::BaseQuadraticFinalStateCost.

Definition at line 64 of file final_state_cost.h.

◆ isLsqFormNonIntegralStateTerm()

bool corbo::QuadraticFinalStateCost::isLsqFormNonIntegralStateTerm ( int  k) const
inlineoverridevirtual

Reimplemented from corbo::StageFunction.

Definition at line 59 of file final_state_cost.h.

◆ setLsqForm()

void corbo::QuadraticFinalStateCost::setLsqForm ( bool  lsq_form)
inline

Definition at line 66 of file final_state_cost.h.

◆ setWeightQf() [1/2]

bool corbo::QuadraticFinalStateCost::setWeightQf ( const Eigen::Ref< const Eigen::MatrixXd > &  Qf)

Definition at line 39 of file final_state_cost.cpp.

◆ setWeightQf() [2/2]

bool corbo::QuadraticFinalStateCost::setWeightQf ( const Eigen::DiagonalMatrix< double, -1 > &  Qf)

Definition at line 62 of file final_state_cost.cpp.

◆ update()

bool corbo::QuadraticFinalStateCost::update ( int  n,
double  t,
ReferenceTrajectoryInterface xref,
ReferenceTrajectoryInterface uref,
ReferenceTrajectoryInterface sref,
bool  single_dt,
const Eigen::VectorXd &  x0,
StagePreprocessor::Ptr  stage_preprocessor,
const std::vector< double > &  dts,
const DiscretizationGridInterface grid 
)
inlineoverridevirtual

Reimplemented from corbo::StageFunction.

Definition at line 70 of file final_state_cost.h.

Member Data Documentation

◆ _diagonal_mode

bool corbo::QuadraticFinalStateCost::_diagonal_mode = false
protected

Definition at line 94 of file final_state_cost.h.

◆ _diagonal_mode_intentionally

bool corbo::QuadraticFinalStateCost::_diagonal_mode_intentionally = false
protected

Definition at line 95 of file final_state_cost.h.

◆ _lsq_form

bool corbo::QuadraticFinalStateCost::_lsq_form = true
protected

Definition at line 96 of file final_state_cost.h.

◆ _Qf

Eigen::MatrixXd corbo::QuadraticFinalStateCost::_Qf
protected

Definition at line 91 of file final_state_cost.h.

◆ _Qf_diag

Eigen::DiagonalMatrix<double, -1> corbo::QuadraticFinalStateCost::_Qf_diag
protected

Definition at line 93 of file final_state_cost.h.

◆ _Qf_diag_sqrt

Eigen::DiagonalMatrix<double, -1> corbo::QuadraticFinalStateCost::_Qf_diag_sqrt
protected

Definition at line 92 of file final_state_cost.h.

◆ _Qf_sqrt

Eigen::MatrixXd corbo::QuadraticFinalStateCost::_Qf_sqrt
protected

Definition at line 90 of file final_state_cost.h.

◆ _x_ref

const ReferenceTrajectoryInterface* corbo::QuadraticFinalStateCost::_x_ref = nullptr
protected

Definition at line 98 of file final_state_cost.h.

◆ _zero_x_ref

bool corbo::QuadraticFinalStateCost::_zero_x_ref = false
protected

Definition at line 99 of file final_state_cost.h.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03