#include <final_state_cost.h>
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 |
QuadraticFinalStateCostRiccati () | |
QuadraticFinalStateCostRiccati (SystemDynamicsInterface::Ptr dynamics, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R) | |
void | setLsqForm (bool lsq_form) |
void | setSystemDynamics (SystemDynamicsInterface::Ptr dynamics) |
bool | setWeightQ (const Eigen::DiagonalMatrix< double, -1 > &Q) |
bool | setWeightQ (const Eigen::Ref< const Eigen::MatrixXd > &Q) |
bool | setWeightR (const Eigen::DiagonalMatrix< double, -1 > &R) |
bool | setWeightR (const Eigen::Ref< const Eigen::MatrixXd > &R) |
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 *) override |
![]() | |
bool | hasIntegralTerms (int k) const final |
bool | hasNonIntegralTerms (int k) const final |
![]() | |
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... | |
Protected Member Functions | |
bool | computeWeightQfSqrt () |
Protected Attributes | |
bool | _are_solved_before = false |
SystemDynamicsInterface::Ptr | _dynamics |
bool | _lsq_form = true |
Eigen::MatrixXd | _Q |
bool | _Q_diagonal_mode_intentionally = false |
Eigen::MatrixXd | _Qf |
Eigen::MatrixXd | _Qf_sqrt |
Eigen::MatrixXd | _R |
bool | _R_diagonal_mode_intentionally = false |
Eigen::VectorXd | _steady_state_u |
Eigen::VectorXd | _steady_state_x |
const ReferenceTrajectoryInterface * | _x_ref = nullptr |
bool | _zero_x_ref = false |
Additional Inherited Members | |
![]() | |
using | ConstPtr = std::shared_ptr< const BaseQuadraticFinalStateCost > |
using | Ptr = std::shared_ptr< BaseQuadraticFinalStateCost > |
![]() | |
using | ConstPtr = std::shared_ptr< const FinalStageCost > |
using | Ptr = std::shared_ptr< FinalStageCost > |
![]() | |
using | ConstPtr = std::shared_ptr< const StageFunction > |
using | Ptr = std::shared_ptr< StageFunction > |
Definition at line 125 of file final_state_cost.h.
|
inline |
Definition at line 128 of file final_state_cost.h.
|
inline |
Definition at line 130 of file final_state_cost.h.
|
overridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 370 of file final_state_cost.cpp.
|
overridevirtual |
Implements corbo::FinalStageCost.
Definition at line 354 of file final_state_cost.cpp.
|
protected |
Definition at line 341 of file final_state_cost.cpp.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Implements corbo::FinalStageCost.
Definition at line 138 of file final_state_cost.h.
|
inlineoverridevirtual |
Implements corbo::FinalStageCost.
Definition at line 140 of file final_state_cost.h.
|
inlineoverridevirtual |
Implements corbo::BaseQuadraticFinalStateCost.
Definition at line 155 of file final_state_cost.h.
|
inline |
Definition at line 153 of file final_state_cost.h.
|
inline |
Definition at line 142 of file final_state_cost.h.
bool corbo::QuadraticFinalStateCostRiccati::setWeightQ | ( | const Eigen::DiagonalMatrix< double, -1 > & | Q | ) |
Definition at line 240 of file final_state_cost.cpp.
bool corbo::QuadraticFinalStateCostRiccati::setWeightQ | ( | const Eigen::Ref< const Eigen::MatrixXd > & | Q | ) |
Definition at line 230 of file final_state_cost.cpp.
bool corbo::QuadraticFinalStateCostRiccati::setWeightR | ( | const Eigen::DiagonalMatrix< double, -1 > & | R | ) |
Definition at line 259 of file final_state_cost.cpp.
bool corbo::QuadraticFinalStateCostRiccati::setWeightR | ( | const Eigen::Ref< const Eigen::MatrixXd > & | R | ) |
Definition at line 249 of file final_state_cost.cpp.
|
overridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 268 of file final_state_cost.cpp.
|
protected |
Definition at line 184 of file final_state_cost.h.
|
protected |
Definition at line 180 of file final_state_cost.h.
|
protected |
Definition at line 183 of file final_state_cost.h.
|
protected |
Definition at line 173 of file final_state_cost.h.
|
protected |
Definition at line 175 of file final_state_cost.h.
|
protected |
Definition at line 179 of file final_state_cost.h.
|
protected |
Definition at line 178 of file final_state_cost.h.
|
protected |
Definition at line 174 of file final_state_cost.h.
|
protected |
Definition at line 176 of file final_state_cost.h.
|
protected |
Definition at line 182 of file final_state_cost.h.
|
protected |
Definition at line 181 of file final_state_cost.h.
|
protected |
Definition at line 186 of file final_state_cost.h.
|
protected |
Definition at line 187 of file final_state_cost.h.