lipm_walking::Controller Struct Reference

Main controller class. More...

#include <lipm_walking/Controller.h>

Inheritance diagram for lipm_walking::Controller:

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Controller (mc_rbdyn::RobotModulePtr robot, double dt, const mc_rtc::Configuration &config, mc_control::ControllerParameters params={})
 Initialize the controller. More...
 
void reset (const mc_control::ControllerResetData &data) override
 Reset controller. More...
 
void addGUIElements (std::shared_ptr< mc_rtc::gui::StateBuilder > gui)
 Add GUI panel. More...
 
void addGUIMarkers (std::shared_ptr< mc_rtc::gui::StateBuilder > gui)
 Add GUI markers. More...
 
void addLogEntries (mc_rtc::Logger &logger)
 Log controller entries. More...
 
void leftFootRatio (double ratio)
 Set fraction of total weight that should be sustained by the left foot. More...
 
void loadFootstepPlan (std::string name)
 Load footstep plan from configuration. More...
 
void updatePlan (const std::string &name)
 
void pauseWalkingCallback (bool verbose=false)
 Callback function called by "Pause walking" button. More...
 
virtual bool run () override
 Main function of the controller, called at every control cycle. More...
 
void startLogSegment (const std::string &label)
 Start new log segment. More...
 
void stopLogSegment ()
 Stop current log segment. More...
 
bool updatePreview ()
 Update horizontal MPC preview. More...
 
void warnIfRobotIsInTheAir ()
 Log a warning message when robot is in the air. More...
 
mc_rbdyn::Robot & controlRobot ()
 Get control robot state. More...
 
double doubleSupportDuration ()
 Get next double support duration. More...
 
bool isLastDSP ()
 True after the last step. More...
 
bool isLastSSP ()
 True during the last step. More...
 
double leftFootRatio ()
 Get fraction of total weight that should be sustained by the left foot. More...
 
double measuredLeftFootRatio ()
 Estimate left foot pressure ratio from force sensors. More...
 
ModelPredictiveControlmpc ()
 Get model predictive control solver. More...
 
const ContactnextContact () const
 Get next contact in plan. More...
 
void nextDoubleSupportDuration (double duration)
 Override next DSP duration. More...
 
mc_planning::Pendulum & pendulum ()
 This getter is only used for consistency with the rest of mc_rtc. More...
 
const ContactprevContact () const
 Get previous contact in plan. More...
 
double singleSupportDuration ()
 Get next SSP duration. More...
 
const Solesole () const
 Get model sole properties. More...
 
std::shared_ptr< mc_tasks::lipm_stabilizer::StabilizerTask > stabilizer ()
 This getter is only used for consistency with the rest of mc_rtc. More...
 
void setContacts (const std::vector< std::pair< mc_tasks::lipm_stabilizer::ContactState, sva::PTransformd >> &contacts, bool fullDoF=false)
 
const ContactsupportContact ()
 Get current support contact. More...
 
const ContacttargetContact ()
 Get current target contact. More...
 
bool isInOpenLoopTicker () const
 Returns true if the controller is running in an open-loop ticker. More...
 

Public Attributes

WalkingState walkingState = WalkingState::Standby
 Current state. More...
 
FootstepPlan plan
 Current footstep plan. More...
 
PlanInterpolator planInterpolator
 Footstep plan interpolator. More...
 
ExternalPlanner externalFootstepPlanner
 Handle requesting/receiving plans from an external planner. More...
 
bool emergencyStop = false
 Emergency flag: if on, the controller stops doing anything. More...
 
bool startWalking = false
 Is the walk started. More...
 
bool pauseWalking = false
 Is the pause-walking behavior engaged? More...
 
bool pauseWalkingRequested = false
 Has user clicked on the "Pause walking" button? More...
 
std::shared_ptr< Previewpreview
 Current solution trajectory from the walking pattern generator. More...
 
std::vector< std::vector< double > > halfSitPose
 Half-sit joint-angle configuration stored when the controller starts. More...
 
std::shared_ptr< mc_tasks::SurfaceTransformTask > swingFootTaskLeft_
 
std::shared_ptr< mc_tasks::SurfaceTransformTask > swingFootTaskRight_
 
bool isWalking = false
 
unsigned nbMPCFailures_ = 0
 Number of times the walking pattern generator failed. More...
 

Detailed Description

Main controller class.

Definition at line 60 of file Controller.h.

Constructor & Destructor Documentation

◆ Controller()

lipm_walking::Controller::Controller ( mc_rbdyn::RobotModulePtr  robot,
double  dt,
const mc_rtc::Configuration &  config,
mc_control::ControllerParameters  params = {} 
)

Initialize the controller.

Parameters
robotRobot model.
dtControl timestep.
configConfiguration dictionary.

Definition at line 39 of file Controller.cpp.

Member Function Documentation

◆ addGUIElements()

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

Add GUI panel.

Parameters
guiGUI handle.

Definition at line 203 of file Controller.cpp.

◆ addGUIMarkers()

void lipm_walking::Controller::addGUIMarkers ( std::shared_ptr< mc_rtc::gui::StateBuilder >  gui)

Add GUI markers.

Parameters
guiGUI handle.

◆ addLogEntries()

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

Log controller entries.

Parameters
loggerLogger.

Definition at line 174 of file Controller.cpp.

◆ controlRobot()

mc_rbdyn::Robot& lipm_walking::Controller::controlRobot ( )
inline

Get control robot state.

Definition at line 159 of file Controller.h.

◆ doubleSupportDuration()

double lipm_walking::Controller::doubleSupportDuration ( )
inline

Get next double support duration.

Definition at line 167 of file Controller.h.

◆ isInOpenLoopTicker()

bool lipm_walking::Controller::isInOpenLoopTicker ( ) const

Returns true if the controller is running in an open-loop ticker.

Definition at line 555 of file Controller.cpp.

◆ isLastDSP()

bool lipm_walking::Controller::isLastDSP ( )
inline

True after the last step.

Definition at line 185 of file Controller.h.

◆ isLastSSP()

bool lipm_walking::Controller::isLastSSP ( )
inline

True during the last step.

Definition at line 193 of file Controller.h.

◆ leftFootRatio() [1/2]

double lipm_walking::Controller::leftFootRatio ( )
inline

Get fraction of total weight that should be sustained by the left foot.

Definition at line 201 of file Controller.h.

◆ leftFootRatio() [2/2]

void lipm_walking::Controller::leftFootRatio ( double  ratio)

Set fraction of total weight that should be sustained by the left foot.

Parameters
ratioNumber between 0 and 1.

Definition at line 342 of file Controller.cpp.

◆ loadFootstepPlan()

void lipm_walking::Controller::loadFootstepPlan ( std::string  name)

Load footstep plan from configuration.

Parameters
namePlan name.

Definition at line 447 of file Controller.cpp.

◆ measuredLeftFootRatio()

double lipm_walking::Controller::measuredLeftFootRatio ( )
inline

Estimate left foot pressure ratio from force sensors.

Definition at line 209 of file Controller.h.

◆ mpc()

ModelPredictiveControl& lipm_walking::Controller::mpc ( )
inline

Get model predictive control solver.

Definition at line 221 of file Controller.h.

◆ nextContact()

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

Get next contact in plan.

Definition at line 229 of file Controller.h.

◆ nextDoubleSupportDuration()

void lipm_walking::Controller::nextDoubleSupportDuration ( double  duration)
inline

Override next DSP duration.

Parameters
durationCustom DSP duration.

Definition at line 239 of file Controller.h.

◆ pauseWalkingCallback()

void lipm_walking::Controller::pauseWalkingCallback ( bool  verbose = false)

Callback function called by "Pause walking" button.

Parameters
verboseTalk to user on the command line.

Definition at line 393 of file Controller.cpp.

◆ pendulum()

mc_planning::Pendulum& lipm_walking::Controller::pendulum ( )
inline

This getter is only used for consistency with the rest of mc_rtc.

Definition at line 247 of file Controller.h.

◆ prevContact()

const Contact& lipm_walking::Controller::prevContact ( ) const
inline

Get previous contact in plan.

Definition at line 255 of file Controller.h.

◆ reset()

void lipm_walking::Controller::reset ( const mc_control::ControllerResetData &  data)
override

Reset controller.

Parameters
dataReset data.

Definition at line 297 of file Controller.cpp.

◆ run()

bool lipm_walking::Controller::run ( )
overridevirtual

Main function of the controller, called at every control cycle.

Definition at line 352 of file Controller.cpp.

◆ setContacts()

void lipm_walking::Controller::setContacts ( const std::vector< std::pair< mc_tasks::lipm_stabilizer::ContactState, sva::PTransformd >> &  contacts,
bool  fullDoF = false 
)

Definition at line 317 of file Controller.cpp.

◆ singleSupportDuration()

double lipm_walking::Controller::singleSupportDuration ( )
inline

Get next SSP duration.

Definition at line 263 of file Controller.h.

◆ sole()

const Sole& lipm_walking::Controller::sole ( ) const
inline

Get model sole properties.

Definition at line 271 of file Controller.h.

◆ stabilizer()

std::shared_ptr<mc_tasks::lipm_stabilizer::StabilizerTask> lipm_walking::Controller::stabilizer ( )
inline

This getter is only used for consistency with the rest of mc_rtc.

Definition at line 279 of file Controller.h.

◆ startLogSegment()

void lipm_walking::Controller::startLogSegment ( const std::string &  label)

Start new log segment.

Parameters
labelSegment label.

Definition at line 523 of file Controller.cpp.

◆ stopLogSegment()

void lipm_walking::Controller::stopLogSegment ( )

Stop current log segment.

Definition at line 533 of file Controller.cpp.

◆ supportContact()

const Contact& lipm_walking::Controller::supportContact ( )
inline

Get current support contact.

Definition at line 291 of file Controller.h.

◆ targetContact()

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

Get current target contact.

Definition at line 299 of file Controller.h.

◆ updatePlan()

void lipm_walking::Controller::updatePlan ( const std::string &  name)

Definition at line 485 of file Controller.cpp.

◆ updatePreview()

bool lipm_walking::Controller::updatePreview ( )

Update horizontal MPC preview.

Definition at line 539 of file Controller.cpp.

◆ warnIfRobotIsInTheAir()

void lipm_walking::Controller::warnIfRobotIsInTheAir ( )

Log a warning message when robot is in the air.

Definition at line 423 of file Controller.cpp.

Member Data Documentation

◆ emergencyStop

bool lipm_walking::Controller::emergencyStop = false

Emergency flag: if on, the controller stops doing anything.

Definition at line 313 of file Controller.h.

◆ externalFootstepPlanner

ExternalPlanner lipm_walking::Controller::externalFootstepPlanner

Handle requesting/receiving plans from an external planner.

Definition at line 312 of file Controller.h.

◆ halfSitPose

std::vector<std::vector<double> > lipm_walking::Controller::halfSitPose

Half-sit joint-angle configuration stored when the controller starts.

Definition at line 319 of file Controller.h.

◆ isWalking

bool lipm_walking::Controller::isWalking = false

Definition at line 323 of file Controller.h.

◆ nbMPCFailures_

unsigned lipm_walking::Controller::nbMPCFailures_ = 0

Number of times the walking pattern generator failed.

Definition at line 324 of file Controller.h.

◆ pauseWalking

bool lipm_walking::Controller::pauseWalking = false

Is the pause-walking behavior engaged?

Definition at line 315 of file Controller.h.

◆ pauseWalkingRequested

bool lipm_walking::Controller::pauseWalkingRequested = false

Has user clicked on the "Pause walking" button?

Definition at line 316 of file Controller.h.

◆ plan

FootstepPlan lipm_walking::Controller::plan

Current footstep plan.

Definition at line 309 of file Controller.h.

◆ planInterpolator

PlanInterpolator lipm_walking::Controller::planInterpolator

Footstep plan interpolator.

Used to generate a simple FootstepPlan when we are not using an external planner

Definition at line 310 of file Controller.h.

◆ preview

std::shared_ptr<Preview> lipm_walking::Controller::preview

Current solution trajectory from the walking pattern generator.

Definition at line 317 of file Controller.h.

◆ startWalking

bool lipm_walking::Controller::startWalking = false

Is the walk started.

Definition at line 314 of file Controller.h.

◆ swingFootTaskLeft_

std::shared_ptr<mc_tasks::SurfaceTransformTask> lipm_walking::Controller::swingFootTaskLeft_

Definition at line 321 of file Controller.h.

◆ swingFootTaskRight_

std::shared_ptr<mc_tasks::SurfaceTransformTask> lipm_walking::Controller::swingFootTaskRight_

Definition at line 322 of file Controller.h.

◆ walkingState

WalkingState lipm_walking::Controller::walkingState = WalkingState::Standby

Current state.

Definition at line 308 of file Controller.h.