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

Linear MPC based on one-dimensional discrete dynamics on step switching. More...

#include <StepMpc.h>

Collaboration diagram for CCC::StepMpc1d:
Collaboration graph
[legend]

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
 

Detailed Description

Linear MPC based on one-dimensional discrete dynamics on step switching.

See the following for a detailed formulation.

Definition at line 17 of file StepMpc.h.

Member Typedef Documentation

◆ _StateSpaceModel

using CCC::StepMpc1d::_StateSpaceModel = StateSpaceModel<2, Eigen::Dynamic, Eigen::Dynamic>

Type of state-space model with fixed state dimension.

Definition at line 23 of file StepMpc.h.

◆ InitialParam

using CCC::StepMpc1d::InitialParam = Eigen::Vector2d

Initial parameter.

First element is CoM position, and second element is CoM velocity.

Definition at line 77 of file StepMpc.h.

Constructor & Destructor Documentation

◆ StepMpc1d()

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

Constructor.

Parameters
com_heightheight of robot CoM [m]
weight_paramobjective weight parameter

Definition at line 130 of file StepMpc.h.

Member Function Documentation

◆ planOnce()

PlannedData CCC::StepMpc1d::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

Friends And Related Function Documentation

◆ StepMpc

friend class StepMpc
friend

Definition at line 19 of file StepMpc.h.

Member Data Documentation

◆ com_height_

double CCC::StepMpc1d::com_height_ = 0
protected

Height of robot CoM [m].

Definition at line 145 of file StepMpc.h.

◆ seq_ext_

std::shared_ptr<VariantSequentialExtension<2> > CCC::StepMpc1d::seq_ext_
protected

Sequential extension of state-space model.

Definition at line 151 of file StepMpc.h.

◆ weight_param_

WeightParam CCC::StepMpc1d::weight_param_
protected

Weight parameter.

Definition at line 148 of file StepMpc.h.


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