Go to the documentation of this file.
25 #ifndef SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_QUADRATIC_CONTROL_COST_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_QUADRATIC_CONTROL_COST_H_
35 class QuadraticControlCost :
public StageCost
65 bool update(
int n,
double t, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, ReferenceTrajectoryInterface* sref,
66 bool single_dt,
const Eigen::VectorXd& x0,
StagePreprocessor::Ptr stage_preprocessor,
const std::vector<double>& dts,
67 const DiscretizationGridInterface* )
override
76 bool checkParameters(
int state_dim,
int control_dim, std::stringstream* issues)
const override;
78 #ifdef MESSAGE_SUPPORT
79 virtual bool fromMessage(
const messages::QuadraticControlCost& message, std::stringstream* issues);
80 virtual void toMessage(messages::QuadraticControlCost& message)
const;
82 bool fromMessage(
const messages::StageCost& message, std::stringstream* issues)
override
84 return fromMessage(message.quadratic_control_cost(), issues);
86 void toMessage(messages::StageCost& message)
const override { toMessage(*message.mutable_quadratic_control_cost()); }
106 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_QUADRATIC_CONTROL_COST_H_
bool hasIntegralTerms(int k) const override
void setIntegralForm(bool integral_form)
void setLsqForm(bool lsq_form)
std::shared_ptr< StagePreprocessor > Ptr
Interface class for reference trajectories.
Eigen::DiagonalMatrix< double, -1 > _R_diag_sqrt
bool isLsqFormNonIntegralControlTerm(int k) 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
virtual bool isZero() const
bool _diagonal_mode_intentionally
std::shared_ptr< StageCost > Ptr
bool checkParameters(int state_dim, int control_dim, std::stringstream *issues) const override
const ReferenceTrajectoryInterface * _u_ref
bool setWeightR(const Eigen::Ref< const Eigen::MatrixXd > &R)
bool hasNonIntegralTerms(int k) const override
#define FACTORY_REGISTER_STAGE_COST(type)
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
A matrix or vector expression mapping an existing expression.
int getIntegralStateControlTermDimension(int k) const override
Eigen::DiagonalMatrix< double, -1 > _R_diag
int getNonIntegralControlTermDimension(int k) const override
StageCost::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:08