lipm_walking::ModelPredictiveControl Struct Reference

Model predictive control problem. More...

#include <lipm_walking/ModelPredictiveControl.h>

Public Member Functions

 ModelPredictiveControl ()
 Initialize new problem. More...
 
void addGUIElements (std::shared_ptr< mc_rtc::gui::StateBuilder > gui)
 Add GUI panel. More...
 
void addLogEntries (mc_rtc::Logger &logger)
 Log stabilizer entries. More...
 
void configure (const mc_rtc::Configuration &)
 Read configuration from dictionary. More...
 
void phaseDurations (double initSupportDuration, double doubleSupportDuration, double targetSupportDuration)
 Set duration of the initial single-support phase. More...
 
bool buildAndSolve ()
 Build and solve the model predictive control quadratic program. More...
 
void comHeight (double height)
 Set CoM height. More...
 
void contacts (Contact initContact, Contact targetContact, Contact nextContact)
 Reset contacts. More...
 
void initState (const Pendulum &pendulum)
 Set the initial CoM state. More...
 
unsigned indexToHrep (unsigned i) const
 Get index of inequality constraints. More...
 
const ContactinitContact () const
 Support contact in the first single-support phase. More...
 
unsigned nbInitSupportSteps () const
 Number of sampling steps in the preview spent in the first single-support phase. More...
 
unsigned nbDoubleSupportSteps () const
 Number of sampling steps in the preview spent in the first double-support phase. More...
 
const ContactnextContact () const
 Support contact in the third single-support phase. More...
 
void sole (const Sole &sole)
 Set model sole properties. More...
 
const std::shared_ptr< Previewsolution () const
 Get solution vector. More...
 
const ContacttargetContact () const
 Support contact in the second single-support phase. More...
 

Public Attributes

Eigen::Vector2d velWeights = {10., 10.}
 Weights of CoM velocity tracking cost. More...
 
double jerkWeight = 1.
 Weight of CoM jerk regularization cost. More...
 
double zmpWeight = 1000.
 Weight of reference ZMP tracking cost. More...
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW constexpr double SAMPLING_PERIOD = 0.1
 Duration of each sampling step in [s]. More...
 
static constexpr unsigned INPUT_SIZE = 2
 Input is the 2D horizontal CoM jerk. More...
 
static constexpr unsigned NB_STEPS = 16
 Number of sampling steps. More...
 
static constexpr unsigned STATE_SIZE = 6
 State is the 6D stacked vector of CoM positions, velocities and accelerations. More...
 

Detailed Description

Model predictive control problem.

This implementation is based on "Trajectory free linear model predictive control for stable walking in the presence of strong perturbations" (Wieber, Humanoids 2006) with the addition of terminal constraints.

Definition at line 52 of file ModelPredictiveControl.h.

Constructor & Destructor Documentation

lipm_walking::ModelPredictiveControl::ModelPredictiveControl ( )

Initialize new problem.

Definition at line 44 of file ModelPredictiveControl.cpp.

Member Function Documentation

void lipm_walking::ModelPredictiveControl::addGUIElements ( std::shared_ptr< mc_rtc::gui::StateBuilder >  gui)

Add GUI panel.

Parameters
guiGUI handle.

Definition at line 87 of file ModelPredictiveControl.cpp.

void lipm_walking::ModelPredictiveControl::addLogEntries ( mc_rtc::Logger &  logger)

Log stabilizer entries.

Parameters
loggerLogger.

Definition at line 129 of file ModelPredictiveControl.cpp.

bool lipm_walking::ModelPredictiveControl::buildAndSolve ( )

Build and solve the model predictive control quadratic program.

Returns
solutionFound Did the solver find a solution?

Definition at line 329 of file ModelPredictiveControl.cpp.

void lipm_walking::ModelPredictiveControl::comHeight ( double  height)
inline

Set CoM height.

Parameters
heightCoM height above contacts.

Definition at line 118 of file ModelPredictiveControl.h.

void lipm_walking::ModelPredictiveControl::configure ( const mc_rtc::Configuration &  config)

Read configuration from dictionary.

Definition at line 76 of file ModelPredictiveControl.cpp.

void lipm_walking::ModelPredictiveControl::contacts ( Contact  initContact,
Contact  targetContact,
Contact  nextContact 
)
inline

Reset contacts.

Parameters
initContactContact used during single-support phase.
targetContactContact used during double-support phases.
nextContactContact coming after targetContact in the plan.

Definition at line 141 of file ModelPredictiveControl.h.

unsigned lipm_walking::ModelPredictiveControl::indexToHrep ( unsigned  i) const
inline

Get index of inequality constraints.

Parameters
iTimestep in preview horizon.
Returns
hrepIndex Index of corresponding ZMP H-rep.
Note
Inequality constraints are the halfspace representation (H-rep) of a polyhedron. In this class we call them H-rep for short.

Definition at line 169 of file ModelPredictiveControl.h.

const Contact& lipm_walking::ModelPredictiveControl::initContact ( ) const
inline

Support contact in the first single-support phase.

Definition at line 177 of file ModelPredictiveControl.h.

void lipm_walking::ModelPredictiveControl::initState ( const Pendulum pendulum)
inline

Set the initial CoM state.

Parameters
pendulumCoM state.

Definition at line 153 of file ModelPredictiveControl.h.

unsigned lipm_walking::ModelPredictiveControl::nbDoubleSupportSteps ( ) const
inline

Number of sampling steps in the preview spent in the first double-support phase.

Definition at line 196 of file ModelPredictiveControl.h.

unsigned lipm_walking::ModelPredictiveControl::nbInitSupportSteps ( ) const
inline

Number of sampling steps in the preview spent in the first single-support phase.

Definition at line 186 of file ModelPredictiveControl.h.

const Contact& lipm_walking::ModelPredictiveControl::nextContact ( ) const
inline

Support contact in the third single-support phase.

Definition at line 204 of file ModelPredictiveControl.h.

void lipm_walking::ModelPredictiveControl::phaseDurations ( double  initSupportDuration,
double  doubleSupportDuration,
double  targetSupportDuration 
)

Set duration of the initial single-support phase.

Parameters
initSupportDurationFirst SSP duration.
doubleSupportDurationFirst DSP duration.
targetSupportDurationSecond SSP duration.

Phase durations don't have to sum up to the total duration of the preview horizon.

If their sum is below total duration, there are two outcomes: if there is a target support phase, a second DSP phase is added from the target contact to the next (full preview mode); otherwise, the first DSP phase is extended until the end of the preview horizon (half preview mode).

If their sum exceeds total duration, phase durations are trimmed starting from the last one.

Definition at line 140 of file ModelPredictiveControl.cpp.

void lipm_walking::ModelPredictiveControl::sole ( const Sole sole)
inline

Set model sole properties.

Parameters
soleSole parameters.

Definition at line 214 of file ModelPredictiveControl.h.

const std::shared_ptr<Preview> lipm_walking::ModelPredictiveControl::solution ( ) const
inline

Get solution vector.

Definition at line 222 of file ModelPredictiveControl.h.

const Contact& lipm_walking::ModelPredictiveControl::targetContact ( ) const
inline

Support contact in the second single-support phase.

Definition at line 230 of file ModelPredictiveControl.h.

Member Data Documentation

constexpr unsigned lipm_walking::ModelPredictiveControl::INPUT_SIZE = 2
static

Input is the 2D horizontal CoM jerk.

Definition at line 57 of file ModelPredictiveControl.h.

double lipm_walking::ModelPredictiveControl::jerkWeight = 1.

Weight of CoM jerk regularization cost.

Definition at line 250 of file ModelPredictiveControl.h.

constexpr unsigned lipm_walking::ModelPredictiveControl::NB_STEPS = 16
static

Number of sampling steps.

Definition at line 58 of file ModelPredictiveControl.h.

constexpr double lipm_walking::ModelPredictiveControl::SAMPLING_PERIOD = 0.1
static

Duration of each sampling step in [s].

Definition at line 56 of file ModelPredictiveControl.h.

constexpr unsigned lipm_walking::ModelPredictiveControl::STATE_SIZE = 6
static

State is the 6D stacked vector of CoM positions, velocities and accelerations.

Definition at line 59 of file ModelPredictiveControl.h.

Eigen::Vector2d lipm_walking::ModelPredictiveControl::velWeights = {10., 10.}

Weights of CoM velocity tracking cost.

Definition at line 249 of file ModelPredictiveControl.h.

double lipm_walking::ModelPredictiveControl::zmpWeight = 1000.

Weight of reference ZMP tracking cost.

Definition at line 251 of file ModelPredictiveControl.h.