centroidal_control_collection
|
Linear MPC based on one-dimensional discrete dynamics on step switching. More...
#include <StepMpc.h>
Classes | |
struct | PlannedData |
Planned data. More... | |
struct | RefData |
Reference data. More... | |
class | StepModel |
Discrete dynamics on step switching. More... | |
struct | WeightParam |
Weight parameter. More... | |
Public Types | |
using | _StateSpaceModel = StateSpaceModel< 2, Eigen::Dynamic, Eigen::Dynamic > |
Type of state-space model with fixed state dimension. More... | |
using | InitialParam = Eigen::Vector2d |
Initial parameter. More... | |
Public Member Functions | |
StepMpc1d (double com_height, const WeightParam &weight_param=WeightParam()) | |
Constructor. More... | |
PlannedData | planOnce (const RefData &ref_data, const InitialParam &initial_param, double current_time) |
Plan one step. More... | |
Protected Attributes | |
double | com_height_ = 0 |
Height of robot CoM [m]. More... | |
WeightParam | weight_param_ |
Weight parameter. More... | |
std::shared_ptr< VariantSequentialExtension< 2 > > | seq_ext_ |
Sequential extension of state-space model. More... | |
Friends | |
class | StepMpc |
Linear MPC based on one-dimensional discrete dynamics on step switching.
See the following for a detailed formulation.
using CCC::StepMpc1d::_StateSpaceModel = StateSpaceModel<2, Eigen::Dynamic, Eigen::Dynamic> |
using CCC::StepMpc1d::InitialParam = Eigen::Vector2d |
|
inline |
PlannedData CCC::StepMpc1d::planOnce | ( | const RefData & | ref_data, |
const InitialParam & | initial_param, | ||
double | current_time | ||
) |
Plan one step.
ref_data | reference data |
initial_param | initial parameter |
current_time | current time (i.e., start time of horizon) [sec] |
|
protected |
|
protected |
|
protected |