centroidal_control_collection
Classes | Public Member Functions | Protected Attributes | List of all members
CCC::StepMpc Class Reference

Linear MPC based on discrete dynamics on step switching. More...

#include <StepMpc.h>

Classes

struct  InitialParam
 Initial parameter. More...
 
struct  PlannedData
 Planned data. More...
 
struct  RefData
 Reference data. More...
 

Public Member Functions

 StepMpc (double com_height, const StepMpc1d::WeightParam &weight_param=StepMpc1d::WeightParam())
 Constructor. More...
 
PlannedData planOnce (const RefData &ref_data, const InitialParam &initial_param, double current_time)
 Plan one step. More...
 

Protected Attributes

std::shared_ptr< StepMpc1dmpc_1d_
 One-dimensional linear MPC. More...
 

Detailed Description

Linear MPC based on discrete dynamics on step switching.

See the following for a detailed formulation.

Todo:
It is assumed that the left and right feet alternate in stepping (i.e., the same foot does not step in succession).

Definition at line 163 of file StepMpc.h.

Constructor & Destructor Documentation

◆ StepMpc()

CCC::StepMpc::StepMpc ( double  com_height,
const StepMpc1d::WeightParam weight_param = StepMpc1d::WeightParam() 
)
inline

Constructor.

Parameters
com_heightheight of robot CoM [m]
weight_paramobjective weight parameter

Definition at line 224 of file StepMpc.h.

Member Function Documentation

◆ planOnce()

PlannedData CCC::StepMpc::planOnce ( const RefData ref_data,
const InitialParam initial_param,
double  current_time 
)

Plan one step.

Parameters
ref_datareference data
initial_paraminitial parameter
current_timecurrent time (i.e., start time of horizon) [sec]
Returns
planned ZMP

Member Data Documentation

◆ mpc_1d_

std::shared_ptr<StepMpc1d> CCC::StepMpc::mpc_1d_
protected

One-dimensional linear MPC.

Definition at line 239 of file StepMpc.h.


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