#include <quadratic_cost.h>
Public Types | |
using | Ptr = std::shared_ptr< QuadraticFormCost > |
![]() | |
using | ConstPtr = std::shared_ptr< const StageCost > |
using | Ptr = std::shared_ptr< StageCost > |
![]() | |
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 | computeIntegralStateControlTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) const override |
void | computeNonIntegralControlTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) const override |
void | computeNonIntegralStateTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override |
StageCost::Ptr | getInstance () const override |
Return a newly created shared instance of the implemented class. More... | |
int | getIntegralStateControlTermDimension (int k) const override |
int | getNonIntegralControlTermDimension (int k) const override |
int | getNonIntegralStateTermDimension (int k) const override |
const Eigen::MatrixXd & | getWeightQ () const |
const Eigen::MatrixXd & | getWeightR () const |
bool | hasIntegralTerms (int k) const override |
bool | hasNonIntegralTerms (int k) const override |
bool | isLsqFormNonIntegralControlTerm (int k) const override |
bool | isLsqFormNonIntegralStateTerm (int k) const override |
QuadraticFormCost () | |
QuadraticFormCost (const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, bool integral_form=false, bool lsq_form=false) | |
void | scaleCurrentWeightQ (double scale) |
void | scaleCurrentWeightR (double scale) |
void | setIntegralForm (bool integral_form) |
void | setLsqForm (bool lsq_form) |
bool | setWeightQ (const Eigen::Ref< const Eigen::MatrixXd > &Q) |
bool | setWeightQ (const Eigen::DiagonalMatrix< double, -1 > &Q) |
bool | setWeightR (const Eigen::Ref< const Eigen::MatrixXd > &R) |
bool | setWeightR (const Eigen::DiagonalMatrix< double, -1 > &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 |
![]() | |
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 | computeNonIntegralControlDeviationTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &u_k, const Eigen::Ref< const Eigen::VectorXd > &u_prev, double dt_prev, Eigen::Ref< Eigen::VectorXd > cost) const |
virtual void | computeNonIntegralDtTerm (int k, double dt, Eigen::Ref< Eigen::VectorXd > cost) const |
virtual void | computeNonIntegralStateControlDtTerm (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) const |
virtual void | computeNonIntegralStateControlTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) 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 | getNonIntegralControlDeviationTermDimension (int k) const |
virtual int | getNonIntegralDtTermDimension (int k) const |
virtual int | getNonIntegralStateControlDtTermDimension (int k) const |
virtual int | getNonIntegralStateControlTermDimension (int k) 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 | isLsqFormNonIntegralDtTerm (int k) const |
virtual | ~StageFunction ()=default |
Default destructor. More... | |
Protected Attributes | |
bool | _integral_form = false |
bool | _lsq_form = true |
Eigen::MatrixXd | _Q |
Eigen::DiagonalMatrix< double, -1 > | _Q_diag |
Eigen::DiagonalMatrix< double, -1 > | _Q_diag_sqrt |
bool | _Q_diagonal_mode = false |
bool | _Q_diagonal_mode_intentionally = false |
Eigen::MatrixXd | _Q_sqrt |
Eigen::MatrixXd | _R |
Eigen::DiagonalMatrix< double, -1 > | _R_diag |
Eigen::DiagonalMatrix< double, -1 > | _R_diag_sqrt |
bool | _R_diagonal_mode = false |
bool | _R_diagonal_mode_intentionally = false |
Eigen::MatrixXd | _R_sqrt |
const ReferenceTrajectoryInterface * | _u_ref = nullptr |
const ReferenceTrajectoryInterface * | _x_ref = nullptr |
bool | _zero_u_ref = false |
bool | _zero_x_ref = false |
Definition at line 35 of file quadratic_cost.h.
using corbo::QuadraticFormCost::Ptr = std::shared_ptr<QuadraticFormCost> |
Definition at line 38 of file quadratic_cost.h.
|
inline |
Definition at line 40 of file quadratic_cost.h.
|
inline |
Definition at line 46 of file quadratic_cost.h.
|
overridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 226 of file quadratic_cost.cpp.
|
overridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 186 of file quadratic_cost.cpp.
|
overridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 143 of file quadratic_cost.cpp.
|
overridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 100 of file quadratic_cost.cpp.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Implements corbo::StageCost.
Definition at line 54 of file quadratic_cost.h.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 61 of file quadratic_cost.h.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 60 of file quadratic_cost.h.
Reimplemented from corbo::StageFunction.
Definition at line 59 of file quadratic_cost.h.
|
inline |
Definition at line 99 of file quadratic_cost.h.
|
inline |
Definition at line 100 of file quadratic_cost.h.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 57 of file quadratic_cost.h.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 56 of file quadratic_cost.h.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 64 of file quadratic_cost.h.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 63 of file quadratic_cost.h.
void corbo::QuadraticFormCost::scaleCurrentWeightQ | ( | double | scale | ) |
Definition at line 278 of file quadratic_cost.cpp.
void corbo::QuadraticFormCost::scaleCurrentWeightR | ( | double | scale | ) |
Definition at line 286 of file quadratic_cost.cpp.
|
inline |
Definition at line 72 of file quadratic_cost.h.
|
inline |
Definition at line 71 of file quadratic_cost.h.
bool corbo::QuadraticFormCost::setWeightQ | ( | const Eigen::Ref< const Eigen::MatrixXd > & | Q | ) |
Definition at line 33 of file quadratic_cost.cpp.
bool corbo::QuadraticFormCost::setWeightQ | ( | const Eigen::DiagonalMatrix< double, -1 > & | Q | ) |
Definition at line 57 of file quadratic_cost.cpp.
bool corbo::QuadraticFormCost::setWeightR | ( | const Eigen::Ref< const Eigen::MatrixXd > & | R | ) |
Definition at line 67 of file quadratic_cost.cpp.
bool corbo::QuadraticFormCost::setWeightR | ( | const Eigen::DiagonalMatrix< double, -1 > & | R | ) |
Definition at line 90 of file quadratic_cost.cpp.
|
inlineoverridevirtual |
Reimplemented from corbo::StageFunction.
Definition at line 81 of file quadratic_cost.h.
|
protected |
Definition at line 128 of file quadratic_cost.h.
|
protected |
Definition at line 127 of file quadratic_cost.h.
|
protected |
Definition at line 116 of file quadratic_cost.h.
|
protected |
Definition at line 120 of file quadratic_cost.h.
|
protected |
Definition at line 118 of file quadratic_cost.h.
|
protected |
Definition at line 122 of file quadratic_cost.h.
|
protected |
Definition at line 123 of file quadratic_cost.h.
|
protected |
Definition at line 114 of file quadratic_cost.h.
|
protected |
Definition at line 117 of file quadratic_cost.h.
|
protected |
Definition at line 121 of file quadratic_cost.h.
|
protected |
Definition at line 119 of file quadratic_cost.h.
|
protected |
Definition at line 124 of file quadratic_cost.h.
|
protected |
Definition at line 125 of file quadratic_cost.h.
|
protected |
Definition at line 115 of file quadratic_cost.h.
|
protected |
Definition at line 131 of file quadratic_cost.h.
|
protected |
Definition at line 130 of file quadratic_cost.h.
|
protected |
Definition at line 133 of file quadratic_cost.h.
|
protected |
Definition at line 132 of file quadratic_cost.h.