centroidal_control_collection
Public Member Functions | Public Attributes | List of all members
CCC::StepMpc1d::WeightParam Struct Reference

Weight parameter. More...

#include <StepMpc.h>

Public Member Functions

 WeightParam (double _free_zmp=1e-2, double _fixed_zmp=1e0, double _double_support=1e0, double _pos=0.0, double _vel=0.0, double _capture_point_abs=1e1, double _capture_point_rel=1e1)
 Constructor. More...
 

Public Attributes

double free_zmp
 Weight of free ZMP (for future contacts) More...
 
double fixed_zmp
 Weight of fixed ZMP (for existing contacts) More...
 
double double_support
 Weight of ZMP in double support phase. More...
 
double pos
 Weight of CoM position. More...
 
double vel
 Weight of CoM velocity. More...
 
double capture_point_abs
 Weight of absolute position of capture point. More...
 
double capture_point_rel
 Weight of relative position of capture point and ZMP. More...
 

Detailed Description

Weight parameter.

Definition at line 80 of file StepMpc.h.

Constructor & Destructor Documentation

◆ WeightParam()

CCC::StepMpc1d::WeightParam::WeightParam ( double  _free_zmp = 1e-2,
double  _fixed_zmp = 1e0,
double  _double_support = 1e0,
double  _pos = 0.0,
double  _vel = 0.0,
double  _capture_point_abs = 1e1,
double  _capture_point_rel = 1e1 
)
inline

Constructor.

Parameters
_free_zmpweight of free ZMP (for future contacts)
_fixed_zmpweight of fixed ZMP (for existing contacts)
_double_supportweight of ZMP in double support phase
_posweight of CoM position
_velweight of CoM velocity
_capture_point_absweight of absolute position of capture point
_capture_point_relweight of relative position of capture point and ZMP

Definition at line 112 of file StepMpc.h.

Member Data Documentation

◆ capture_point_abs

double CCC::StepMpc1d::WeightParam::capture_point_abs

Weight of absolute position of capture point.

Definition at line 98 of file StepMpc.h.

◆ capture_point_rel

double CCC::StepMpc1d::WeightParam::capture_point_rel

Weight of relative position of capture point and ZMP.

Definition at line 101 of file StepMpc.h.

◆ double_support

double CCC::StepMpc1d::WeightParam::double_support

Weight of ZMP in double support phase.

Definition at line 89 of file StepMpc.h.

◆ fixed_zmp

double CCC::StepMpc1d::WeightParam::fixed_zmp

Weight of fixed ZMP (for existing contacts)

Definition at line 86 of file StepMpc.h.

◆ free_zmp

double CCC::StepMpc1d::WeightParam::free_zmp

Weight of free ZMP (for future contacts)

Definition at line 83 of file StepMpc.h.

◆ pos

double CCC::StepMpc1d::WeightParam::pos

Weight of CoM position.

Definition at line 92 of file StepMpc.h.

◆ vel

double CCC::StepMpc1d::WeightParam::vel

Weight of CoM velocity.

Definition at line 95 of file StepMpc.h.


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