centroidal_control_collection
Classes | Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
CCC::PreviewControl< StateDim, InputDim, OutputDim > Class Template Reference

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< _StateSpaceModelmodel_
 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...
 

Detailed Description

template<int StateDim, int InputDim, int OutputDim>
class CCC::PreviewControl< StateDim, InputDim, OutputDim >

Preview control.

Template Parameters
StateDimstate dimension
InputDiminput dimension
OutputDimoutput dimension

See the following for a detailed formulation.

Definition at line 22 of file PreviewControl.h.

Member Typedef Documentation

◆ _StateSpaceModel

template<int StateDim, int InputDim, int OutputDim>
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::_StateSpaceModel = StateSpaceModel<StateDim, InputDim, OutputDim>

Type of state-space model.

Definition at line 35 of file PreviewControl.h.

◆ InputDimVector

template<int StateDim, int InputDim, int OutputDim>
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::InputDimVector = Eigen::Matrix<double, InputDim, 1>

Type of input vector.

Definition at line 29 of file PreviewControl.h.

◆ OutputDimVector

template<int StateDim, int InputDim, int OutputDim>
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::OutputDimVector = Eigen::Matrix<double, OutputDim, 1>

Type of output vector.

Definition at line 32 of file PreviewControl.h.

◆ StateDimVector

template<int StateDim, int InputDim, int OutputDim>
using CCC::PreviewControl< StateDim, InputDim, OutputDim >::StateDimVector = Eigen::Matrix<double, StateDim, 1>

Type of state vector.

Definition at line 26 of file PreviewControl.h.

Constructor & Destructor Documentation

◆ PreviewControl()

template<int StateDim, int InputDim, int OutputDim>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CCC::PreviewControl< StateDim, InputDim, OutputDim >::PreviewControl ( const std::shared_ptr< _StateSpaceModel > &  model,
double  horizon_duration,
double  horizon_dt,
const WeightParam weight_param 
)
inline

Constructor.

Parameters
modelstate-space model
horizon_durationhorizon duration [sec]
horizon_dtdiscretization timestep in horizon [sec]
weight_paramobjective weight parameter

Definition at line 67 of file PreviewControl.h.

Member Function Documentation

◆ calcGain()

template<int StateDim, int InputDim, int OutputDim>
void CCC::PreviewControl< StateDim, InputDim, OutputDim >::calcGain ( const WeightParam weight_param)
inlineprotected

Calculate the gain of the preview control.

Definition at line 93 of file PreviewControl.h.

◆ calcOptimalInput()

template<int StateDim, int InputDim, int OutputDim>
InputDimVector CCC::PreviewControl< StateDim, InputDim, OutputDim >::calcOptimalInput ( const StateDimVector x,
const Eigen::VectorXd &  ref_output_seq 
) const
inline

Calculate optimal input.

Parameters
xstate
ref_output_seqsequence of reference output

Definition at line 86 of file PreviewControl.h.

Member Data Documentation

◆ F_

template<int StateDim, int InputDim, int OutputDim>
Eigen::Matrix<double, InputDim, Eigen::Dynamic> CCC::PreviewControl< StateDim, InputDim, OutputDim >::F_
protected

Preview gain.

Definition at line 195 of file PreviewControl.h.

◆ horizon_dt_

template<int StateDim, int InputDim, int OutputDim>
double CCC::PreviewControl< StateDim, InputDim, OutputDim >::horizon_dt_ = 0

Discretization timestep in horizon [sec].

Definition at line 179 of file PreviewControl.h.

◆ horizon_steps_

template<int StateDim, int InputDim, int OutputDim>
int CCC::PreviewControl< StateDim, InputDim, OutputDim >::horizon_steps_ = -1

Number of steps in horizon.

Definition at line 182 of file PreviewControl.h.

◆ K_

template<int StateDim, int InputDim, int OutputDim>
Eigen::Matrix<double, InputDim, StateDim> CCC::PreviewControl< StateDim, InputDim, OutputDim >::K_
protected

Feedback gain.

Definition at line 192 of file PreviewControl.h.

◆ model_

template<int StateDim, int InputDim, int OutputDim>
std::shared_ptr<_StateSpaceModel> CCC::PreviewControl< StateDim, InputDim, OutputDim >::model_

State-space model.

Definition at line 176 of file PreviewControl.h.

◆ P_

template<int StateDim, int InputDim, int OutputDim>
Eigen::Matrix<double, StateDim, StateDim> CCC::PreviewControl< StateDim, InputDim, OutputDim >::P_
protected

Solution of the algebraic Riccati equation.

Definition at line 189 of file PreviewControl.h.

◆ riccati_error_

template<int StateDim, int InputDim, int OutputDim>
double CCC::PreviewControl< StateDim, InputDim, OutputDim >::riccati_error_ = 0

Error of algebraic Riccati equation.

Definition at line 185 of file PreviewControl.h.


The documentation for this class was generated from the following file: