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

#include <final_state_constraints.h>

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

Public Types

using ConstPtr = std::shared_ptr< const TerminalBallInheritFromCost >
 
using Ptr = std::shared_ptr< TerminalBallInheritFromCost >
 
- Public Types inherited from corbo::TerminalBall
using ConstPtr = std::shared_ptr< const TerminalBall >
 
using Ptr = std::shared_ptr< TerminalBall >
 
- Public Types inherited from corbo::FinalStageConstraint
using ConstPtr = std::shared_ptr< const FinalStageConstraint >
 
using Ptr = std::shared_ptr< FinalStageConstraint >
 
- 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, FinalStageCost::ConstPtr final_stage_cost, std::stringstream *issues) const override
 
void computeNonIntegralStateTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
 
FinalStageConstraint::Ptr getInstance () const override
 Return a newly created shared instance of the implemented class. More...
 
int getNonIntegralStateTermDimension (int k) const override
 
void setWeightS (const Eigen::Ref< const Eigen::MatrixXd > &S)=delete
 
bool setWeightS (const Eigen::DiagonalMatrix< double, -1 > &S)=delete
 
 TerminalBallInheritFromCost ()=default
 
bool update (int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, FinalStageCost::ConstPtr final_stage_cost, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *) override
 
- Public Member Functions inherited from corbo::TerminalBall
double getGamma ()
 
const Eigen::MatrixXd & getWeightS () const
 
bool isEqualityConstraint () const override
 
void setGamma (double gamma)
 
bool setWeightS (const Eigen::Ref< const Eigen::MatrixXd > &S)
 
bool setWeightS (const Eigen::DiagonalMatrix< double, -1 > &S)
 
 TerminalBall ()=default
 
 TerminalBall (const Eigen::Ref< const Eigen::MatrixXd > &S, double gamma)
 
- Public Member Functions inherited from corbo::FinalStageConstraint
bool hasIntegralTerms (int k) const final
 
bool hasNonIntegralTerms (int k) const final
 
bool isInequalityConstraint () const
 
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) final
 
- Public Member Functions inherited from corbo::StageFunction
virtual bool checkParameters (int state_dim, int control_dim, std::stringstream *issues) const
 
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 bool isLsqFormNonIntegralStateTerm (int k) const
 
virtual ~StageFunction ()=default
 Default destructor. More...
 

Public Attributes

double _gamma = 0.0
 

Additional Inherited Members

- Protected Attributes inherited from corbo::TerminalBall
bool _diagonal_mode = false
 
bool _diagonal_mode_intentionally = false
 
double _gamma = 0.0
 
Eigen::MatrixXd _S
 
Eigen::DiagonalMatrix< double, -1 > _S_diag
 
const ReferenceTrajectoryInterface_x_ref = nullptr
 
bool _zero_x_ref = false
 

Detailed Description

Definition at line 98 of file final_state_constraints.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 102 of file final_state_constraints.h.

◆ Ptr

Definition at line 101 of file final_state_constraints.h.

Constructor & Destructor Documentation

◆ TerminalBallInheritFromCost()

corbo::TerminalBallInheritFromCost::TerminalBallInheritFromCost ( )
default

Member Function Documentation

◆ checkParameters()

bool corbo::TerminalBallInheritFromCost::checkParameters ( int  state_dim,
int  control_dim,
FinalStageCost::ConstPtr  final_stage_cost,
std::stringstream *  issues 
) const
overridevirtual

Reimplemented from corbo::TerminalBall.

Definition at line 221 of file final_state_constraints.cpp.

◆ computeNonIntegralStateTerm()

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

Reimplemented from corbo::TerminalBall.

Definition at line 197 of file final_state_constraints.cpp.

◆ getInstance()

FinalStageConstraint::Ptr corbo::TerminalBallInheritFromCost::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Reimplemented from corbo::TerminalBall.

Definition at line 106 of file final_state_constraints.h.

◆ getNonIntegralStateTermDimension()

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

Reimplemented from corbo::TerminalBall.

Definition at line 108 of file final_state_constraints.h.

◆ setWeightS() [1/2]

void corbo::TerminalBallInheritFromCost::setWeightS ( const Eigen::Ref< const Eigen::MatrixXd > &  S)
delete

◆ setWeightS() [2/2]

bool corbo::TerminalBallInheritFromCost::setWeightS ( const Eigen::DiagonalMatrix< double, -1 > &  S)
delete

◆ update()

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

Reimplemented from corbo::TerminalBall.

Definition at line 171 of file final_state_constraints.cpp.

Member Data Documentation

◆ _gamma

double corbo::TerminalBallInheritFromCost::_gamma = 0.0

Definition at line 126 of file final_state_constraints.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