centroidal_control_collection
|
Preview control. More...
#include <PreviewControl.h>
Classes | |
struct | WeightParam |
Weight parameter. More... | |
Public Types | |
using | StateDimVector = Eigen::Matrix< double, StateDim, 1 > |
Type of state vector. More... | |
using | InputDimVector = Eigen::Matrix< double, InputDim, 1 > |
Type of input vector. More... | |
using | OutputDimVector = Eigen::Matrix< double, OutputDim, 1 > |
Type of output vector. More... | |
using | _StateSpaceModel = StateSpaceModel< StateDim, InputDim, OutputDim > |
Type of state-space model. More... | |
Public Member Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | PreviewControl (const std::shared_ptr< _StateSpaceModel > &model, double horizon_duration, double horizon_dt, const WeightParam &weight_param) |
Constructor. More... | |
InputDimVector | calcOptimalInput (const StateDimVector &x, const Eigen::VectorXd &ref_output_seq) const |
Calculate optimal input. More... | |
Public Attributes | |
std::shared_ptr< _StateSpaceModel > | model_ |
State-space model. More... | |
double | horizon_dt_ = 0 |
Discretization timestep in horizon [sec]. More... | |
int | horizon_steps_ = -1 |
Number of steps in horizon. More... | |
double | riccati_error_ = 0 |
Error of algebraic Riccati equation. More... | |
Protected Member Functions | |
void | calcGain (const WeightParam &weight_param) |
Calculate the gain of the preview control. More... | |
Protected Attributes | |
Eigen::Matrix< double, StateDim, StateDim > | P_ |
Solution of the algebraic Riccati equation. More... | |
Eigen::Matrix< double, InputDim, StateDim > | K_ |
Feedback gain. More... | |
Eigen::Matrix< double, InputDim, Eigen::Dynamic > | F_ |
Preview gain. More... | |
Preview control.
StateDim | state dimension |
InputDim | input dimension |
OutputDim | output dimension |
See the following for a detailed formulation.
Definition at line 22 of file PreviewControl.h.
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::_StateSpaceModel = StateSpaceModel<StateDim, InputDim, OutputDim> |
Type of state-space model.
Definition at line 35 of file PreviewControl.h.
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::InputDimVector = Eigen::Matrix<double, InputDim, 1> |
Type of input vector.
Definition at line 29 of file PreviewControl.h.
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::OutputDimVector = Eigen::Matrix<double, OutputDim, 1> |
Type of output vector.
Definition at line 32 of file PreviewControl.h.
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::StateDimVector = Eigen::Matrix<double, StateDim, 1> |
Type of state vector.
Definition at line 26 of file PreviewControl.h.
|
inline |
Constructor.
model | state-space model |
horizon_duration | horizon duration [sec] |
horizon_dt | discretization timestep in horizon [sec] |
weight_param | objective weight parameter |
Definition at line 67 of file PreviewControl.h.
|
inlineprotected |
Calculate the gain of the preview control.
Definition at line 93 of file PreviewControl.h.
|
inline |
Calculate optimal input.
x | state |
ref_output_seq | sequence of reference output |
Definition at line 86 of file PreviewControl.h.
|
protected |
Preview gain.
Definition at line 195 of file PreviewControl.h.
double CCC::PreviewControl< StateDim, InputDim, OutputDim >::horizon_dt_ = 0 |
Discretization timestep in horizon [sec].
Definition at line 179 of file PreviewControl.h.
int CCC::PreviewControl< StateDim, InputDim, OutputDim >::horizon_steps_ = -1 |
Number of steps in horizon.
Definition at line 182 of file PreviewControl.h.
|
protected |
Feedback gain.
Definition at line 192 of file PreviewControl.h.
std::shared_ptr<_StateSpaceModel> CCC::PreviewControl< StateDim, InputDim, OutputDim >::model_ |
State-space model.
Definition at line 176 of file PreviewControl.h.
|
protected |
Solution of the algebraic Riccati equation.
Definition at line 189 of file PreviewControl.h.
double CCC::PreviewControl< StateDim, InputDim, OutputDim >::riccati_error_ = 0 |
Error of algebraic Riccati equation.
Definition at line 185 of file PreviewControl.h.