centroidal_control_collection
|
Preview control for one-dimensional centroidal model. More...
#include <PreviewControlCentroidal.h>
Classes | |
class | CentroidalModel1d |
State-space model of one-dimensional centroidal dynamics with jerk input and position and wrench output. More... | |
struct | WeightParam |
Weight parameter. More... | |
Public Types | |
using | RefData = Eigen::Vector2d |
Reference data. More... | |
using | InitialParam = PreviewControl< 3, 1, 2 >::StateDimVector |
Initial parameter. More... | |
Public Types inherited from CCC::PreviewControl< 3, 1, 2 > | |
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 | |
PreviewControlCentroidal1d (double inertia_param, double horizon_duration, double horizon_dt, const WeightParam &weight_param=WeightParam()) | |
Constructor. More... | |
Public Member Functions inherited from CCC::PreviewControl< 3, 1, 2 > | |
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... | |
Protected Member Functions | |
double | procOnce (const Eigen::VectorXd &ref_output_seq, const InitialParam &initial_param, double current_time, double control_dt) const |
Process one step. More... | |
Protected Member Functions inherited from CCC::PreviewControl< 3, 1, 2 > | |
void | calcGain (const WeightParam &weight_param) |
Calculate the gain of the preview control. More... | |
Friends | |
class | PreviewControlCentroidal |
Additional Inherited Members | |
Public Attributes inherited from CCC::PreviewControl< 3, 1, 2 > | |
std::shared_ptr< _StateSpaceModel > | model_ |
State-space model. More... | |
double | horizon_dt_ |
Discretization timestep in horizon [sec]. More... | |
int | horizon_steps_ |
Number of steps in horizon. More... | |
double | riccati_error_ |
Error of algebraic Riccati equation. More... | |
Protected Attributes inherited from CCC::PreviewControl< 3, 1, 2 > | |
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 for one-dimensional centroidal model.
See the following for a detailed formulation.
Definition at line 24 of file PreviewControlCentroidal.h.
using CCC::PreviewControlCentroidal1d::InitialParam = PreviewControl<3, 1, 2>::StateDimVector |
Initial parameter.
For the position components, it consists of the position, velocity, and acceleration of the CoM. For the orientation components, it consists of the orientation, angular velocity, and angular acceleration of the base link.
Definition at line 42 of file PreviewControlCentroidal.h.
using CCC::PreviewControlCentroidal1d::RefData = Eigen::Vector2d |
Reference data.
For the position components, the first element is the CoM position and the second element is the force; for the orientation components, the first element is the base link orientation and the second element is the moment.
Definition at line 34 of file PreviewControlCentroidal.h.
|
inline |
Constructor.
inertia_param | inertia parameter (mass [kg] for the position components, moment of inertia [kg m^2] for the orientation components) |
horizon_duration | horizon duration [sec] |
horizon_dt | discretization timestep in horizon [sec] |
weight_param | objective weight parameter |
Definition at line 112 of file PreviewControlCentroidal.h.
|
protected |
Process one step.
|
friend |
Definition at line 26 of file PreviewControlCentroidal.h.