mc_tasks::lipm_stabilizer::StabilizerTask Struct Reference

#include <mc_tasks/lipm_stabilizer/StabilizerTask.h>

Inheritance diagram for mc_tasks::lipm_stabilizer::StabilizerTask:
Collaboration diagram for mc_tasks::lipm_stabilizer::StabilizerTask:

Classes

struct  EnumClassHash
 Workaround a C++11 standard bug: no specialization of the hash functor exists for enum types. Fixed in GCC 6.1 and clang's libc++ in 2013. More...
 
struct  ExternalWrench
 External wrench. More...
 

Public Member Functions

 StabilizerTask (const mc_rbdyn::Robots &robots, const mc_rbdyn::Robots &realRobots, unsigned int robotIndex, const std::string &leftSurface, const std::string &rightSurface, const std::string &torsoBodyName, double dt)
 Creates a stabilizer meta task. More...
 
 StabilizerTask (const mc_rbdyn::Robots &robots, const mc_rbdyn::Robots &realRobots, unsigned int robotIndex, double dt)
 Creates a stabilizer meta task. More...
 
void name (const std::string &name) override
 
void reset () override
 Resets the stabilizer tasks and parameters to their default configuration. More...
 
Eigen::VectorXd eval () const override
 Returns the task error. More...
 
Eigen::VectorXd speed () const override
 Returns the task velocity. More...
 
void enable ()
 Enables stabilizer. More...
 
void disable ()
 
void configure (const StabilizerConfiguration &config)
 
void commitConfig ()
 Use the current configuration as the new default. More...
 
void load (mc_solver::QPSolver &, const mc_rtc::Configuration &config) override
 Load targets and contacts from configuration. More...
 
const StabilizerConfigurationconfig () const
 Get current stabilizer's configuration (including changes from GUI/code) More...
 
const StabilizerConfigurationcommitedConfig () const
 Get last commited configuration. More...
 
void reconfigure ()
 
void run ()
 
void setContacts (const ContactDescriptionVector &contacts)
 
void setContacts (const std::vector< std::pair< ContactState, sva::PTransformd >> &contacts)
 Helper to set contacts with a provided target pose. More...
 
void setContacts (const std::vector< ContactState > &contacts)
 
const sva::PTransformd & contactAnklePose (ContactState s) const
 Projected pose of the ankle frame in the contact frame. More...
 
const std::string & footSurface (ContactState s) const
 
double leftFootRatio () const noexcept
 Interpolation paremeter between left and right foot. More...
 
sva::PTransformd anchorFrame (const mc_rbdyn::Robot &robot) const
 computes the anchorFrame compatible with the state observers (e.g KinematicInertial) More...
 
void staticTarget (const Eigen::Vector3d &com, double zmpHeight=0)
 
void target (const Eigen::Vector3d &com, const Eigen::Vector3d &comd, const Eigen::Vector3d &comdd, const Eigen::Vector3d &zmp, const Eigen::Vector3d &zmpd=Eigen::Vector3d::Zero())
 Provides a dynamic target to the stabilizer. More...
 
const Eigen::Vector3d & targetCoMRaw () const noexcept
 Return the raw CoM target as provided by target(). More...
 
const Eigen::Vector3d & targetCoM () const noexcept
 Returns the CoM target used for stabilization. More...
 
const Eigen::Vector3d & targetCoMVelocity () const noexcept
 
const Eigen::Vector3d & targetCoMAcceleration () const noexcept
 
const Eigen::Vector3d & targetZMP () const noexcept
 
const Eigen::Vector3d & targetZMPVelocity () const noexcept
 
ContactState supportFoot () const noexcept
 
void supportFoot (const ContactState &foot) noexcept
 
void horizonReference (const std::vector< Eigen::Vector2d > &ref, const double delta) noexcept
 Set the reference zmp sequence to distribute between the CoP task (Only in double support) More...
 
void setExternalWrenches (const std::vector< std::string > &surfaceNames, const std::vector< sva::ForceVecd > &targetWrenches, const std::vector< sva::MotionVecd > &gains)
 Set the wrench that the robot expects to receive from the external contacts. More...
 
const std::vector< ExternalWrench > & externalWrenches () const noexcept
 
const Eigen::Vector3d & distribZMP () const noexcept
 
const Eigen::Vector3d & measuredDCM () noexcept
 
const Eigen::Vector2d biasDCM () noexcept
 
Eigen::Vector2d filteredDCM () const noexcept
 
const Eigen::Vector3d & measuredZMP () noexcept
 
const Eigen::Vector3d & measuredCoM () noexcept
 
const Eigen::Vector3d & measuredCoMd () noexcept
 
const Eigen::Vector3d & measuredFilteredNetForces () const noexcept
 
const Eigen::Vector3d & comOffsetTarget () noexcept
 
const Eigen::Vector3d & comOffsetMeasured () const noexcept
 
double zmpCoeffMeasured () const noexcept
 
bool inContact (ContactState state) const noexcept
 
bool inDoubleSupport () const noexcept
 
const mc_rbdyn::Robotrobot () const noexcept
 
const mc_rbdyn::RobotrealRobot () const noexcept
 
virtual void name (const std::string &name)
 
const std::string & name () const
 
- Public Member Functions inherited from mc_tasks::MetaTask
 MetaTask ()
 
virtual ~MetaTask ()
 
const std::string & type () const
 
const std::string & name () const
 
size_t iterInSolver () const noexcept
 Get the number of iterations since the task was added to the solver. More...
 
void resetIterInSolver () noexcept
 Set the number of iterations since the task was added to the solver to zero. More...
 
void incrementIterInSolver () noexcept
 Increment the number of iterations since the task was added to the solver. More...
 
Backend backend () const noexcept
 

Protected Attributes

mc_filter::ExponentialMovingAverage< Eigen::Vector3d > dcmIntegrator_
 
mc_filter::LowPassCompose< Eigen::Vector3d > dcmDerivator_
 
bool inTheAir_ = false
 
bool wasInTheAir_ = false
 
bool wasEnabled_ = true
 
Eigen::Vector3d dfForceError_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d dfError_ = Eigen::Vector3d::Zero()
 
double dt_ = 0.005
 
double leftFootRatio_ = 0.5
 
double mass_ = 38.
 
double runTime_ = 0.
 
double vdcHeightError_ = 0
 
sva::ForceVecd desiredWrench_ = sva::ForceVecd::Zero()
 
sva::ForceVecd distribWrench_ = sva::ForceVecd::Zero()
 
Eigen::Vector3d distribZMP_
 
sva::PTransformd zmpFrame_ = sva::PTransformd::Identity()
 
std::vector< Eigen::Vector2d > horizonZmpRef_
 
double horizonDelta_ = 0.05
 
bool horizonCoPDistribution_ = false
 
bool horizonRefUpdated_ = false
 
Eigen::Vector2d modeledCoPLeft_ = Eigen::Vector2d::Zero()
 
Eigen::Vector2d modeledCoPRight_ = Eigen::Vector2d::Zero()
 
Eigen::Vector2d delayedTargetCoPLeft_ = Eigen::Vector2d::Zero()
 
Eigen::Vector2d delayedTargetCoPRight_ = Eigen::Vector2d::Zero()
 
double delayedTargetFzLeft_ = 0
 
double delayedTargetFzRight_ = 0
 
double tComputation_ = 0.
 
double modeledFzRight_ = 0.
 
double modeledFzLeft_ = 0.
 
double desiredFzLeft_ = 0.
 
double desiredFzRight_ = 0.
 
Eigen::Vector2d QPCoPLeft_
 
Eigen::Vector2d QPCoPRight_
 
Eigen::Vector2d distribCheck_ = Eigen::Vector2d::Zero()
 
mc_filter::LowPass< Eigen::Vector3d > fSumFilter_
 
ContactState supportFoot_ = ContactState::Left
 
Members related to stabilization in the presence of external wrenches

Adding an offset to the CoM for the predictable / measurable external wrenches on the robot surface.

std::vector< ExternalWrenchextWrenches_
 
sva::ForceVecd extWrenchSumTarget_ = sva::ForceVecd::Zero()
 
sva::ForceVecd extWrenchSumMeasured_ = sva::ForceVecd::Zero()
 
Eigen::Vector3d comOffsetTarget_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d comOffsetMeasured_ = Eigen::Vector3d::Zero()
 
double zmpCoefTarget_ = 1
 
double zmpCoefMeasured_ = 1
 
Eigen::Vector3d comOffsetErr_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d comOffsetErrCoM_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d comOffsetErrZMP_ = Eigen::Vector3d::Zero()
 
mc_filter::LowPass< sva::ForceVecd > extWrenchSumLowPass_
 
mc_filter::LowPass< Eigen::Vector3d > comOffsetLowPass_
 
mc_filter::LowPass< Eigen::Vector3d > comOffsetLowPassCoM_
 
mc_filter::StationaryOffset< Eigen::Vector3d > comOffsetDerivator_
 
- Protected Attributes inherited from mc_tasks::MetaTask
Backend backend_
 
std::string type_
 
std::string name_
 
size_t iterInSolver_ = 0
 

Setters to reconfigure the stabilizer online

Setters for the main parameters of the stabilizer. For safety purposes, values are clamped against the maximum values defined by the stabilizer configuration.

See also
StabilizerConfiguration for details on each of these parameters.
config() Access the current stabilizer configuration values
commitConfig() Make the current configuration the new default
std::unordered_map< ContactState, internal::Contact, EnumClassHash, std::equal_to< ContactState >, Eigen::aligned_allocator< std::pair< const ContactState, internal::Contact > > > contacts_
 
std::vector< ContactState > addContacts_
 
std::unordered_map< ContactState, std::shared_ptr< mc_tasks::force::CoPTask >, EnumClassHashfootTasks
 
std::vector< std::shared_ptr< mc_tasks::force::CoPTask > > contactTasks
 
std::vector< std::string > contactSensors
 
std::vector< std::vector< Eigen::Vector3d > > supportPolygons_
 
Eigen::Vector2d supportMin_ = Eigen::Vector2d::Zero()
 
Eigen::Vector2d supportMax_ = Eigen::Vector2d::Zero()
 
std::shared_ptr< mc_tasks::CoMTaskcomTask
 
std::shared_ptr< mc_tasks::OrientationTaskpelvisTask
 
std::shared_ptr< mc_tasks::OrientationTasktorsoTask
 
const mc_rbdyn::Robotsrobots_
 
const mc_rbdyn::RobotsrealRobots_
 
unsigned int robotIndex_
 
Eigen::Vector3d comTargetRaw_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d comTarget_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d comdTarget_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d comddTarget_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d zmpTarget_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d zmpdTarget_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d dcmTarget_ = Eigen::Vector3d::Zero()
 
double omega_ = 3.4
 
double t_ = 0.
 
StabilizerConfiguration defaultConfig_
 
StabilizerConfiguration lastConfig_
 
StabilizerConfiguration disableConfig_
 
StabilizerConfiguration c_
 
bool reconfigure_ = true
 
bool enabled_ = true
 
Eigen::QuadProgDense qpSolver_
 
Eigen::Vector3d dcmAverageError_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d dcmError_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d dcmVelError_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d measuredCoM_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d measuredCoMd_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d measuredCoMdd_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d measuredZMP_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d measuredDCM_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d measuredDCMUnbiased_ = Eigen::Vector3d::Zero()
 Measured DCM (only used for logging) More...
 
Eigen::Vector3d measuredCoMUnbiased_ = Eigen::Vector3d::Zero()
 DCM unbiased (only used for logging) More...
 
sva::ForceVecd measuredNetWrench_ = sva::ForceVecd::Zero()
 CoM unbiased (only used for logging) More...
 
bool zmpccOnlyDS_ = true
 
ZMPCC zmpcc_
 
stateObservation::LipmDcmEstimator dcmEstimator_
 
bool dcmEstimatorNeedsReset_ = true
 
void torsoPitch (double pitch) noexcept
 
double omega () const
 
void torsoWeight (double weight) noexcept
 
void torsoStiffness (double stiffness) noexcept
 
void pelvisWeight (double weight) noexcept
 
void pelvisStiffness (double stiffness) noexcept
 
void dcmGains (double p, double i, double d) noexcept
 
void dcmGains (const Eigen::Vector2d &p, const Eigen::Vector2d &i, const Eigen::Vector2d &d) noexcept
 
void dcmIntegratorTimeConstant (double dcmIntegratorTimeConstant) noexcept
 
MC_RTC_DEPRECATED void dcmDerivatorTimeConstant (double T) noexcept
 
void dcmDerivatorCutoffPeriod (double T) noexcept
 
void extWrenchSumLowPassCutoffPeriod (double cutoffPeriod) noexcept
 
void comOffsetLowPassCutoffPeriod (double cutoffPeriod) noexcept
 
void comOffsetLowPassCoMCutoffPeriod (double cutoffPeriod) noexcept
 
void comOffsetDerivatorTimeConstant (double timeConstant) noexcept
 
void comWeight (double weight) noexcept
 
void comStiffness (const Eigen::Vector3d &stiffness) noexcept
 
void contactWeight (double weight) noexcept
 
void contactStiffness (const sva::MotionVecd &stiffness) noexcept
 
void contactDamping (const sva::MotionVecd &damping) noexcept
 
void copAdmittance (const Eigen::Vector2d &copAdmittance) noexcept
 
void copMaxVel (const sva::MotionVecd &copMaxVel) noexcept
 
void copVelFilterGain (double gain) noexcept
 
double copVelFilterGain () const noexcept
 
void vdcFrequency (double freq) noexcept
 
void vdcStiffness (double stiffness) noexcept
 
void dfAdmittance (Eigen::Vector3d dfAdmittance) noexcept
 
void dfDamping (Eigen::Vector3d dfDamping) noexcept
 
void fdqpWeights (const FDQPWeights &fdqp) noexcept
 
void safetyThresholds (const SafetyThresholds &thresholds) noexcept
 Changes the safety thresholds. More...
 
void dcmBiasEstimatorConfiguration (const DCMBiasEstimatorConfiguration &biasConfig) noexcept
 Changes the parameters of the DCM bias estimator. More...
 
const DCMBiasEstimatorConfigurationdcmBiasEstimatorConfiguration () const noexcept
 Get parameters of the DCM bias estimator. More...
 
void externalWrenchConfiguration (const ExternalWrenchConfiguration &extWrenchConfig) noexcept
 Changes the parameters for the external wrenches. More...
 
const ExternalWrenchConfigurationexternalWrenchConfiguration () const noexcept
 Get the parameters for the external wrenches. More...
 
void addToSolver (mc_solver::QPSolver &solver) override
 
void removeFromSolver (mc_solver::QPSolver &solver) override
 
void removeFromGUI (mc_rtc::gui::StateBuilder &) override
 
void update (mc_solver::QPSolver &) override
 
void addToLogger (mc_rtc::Logger &) override
 
void removeFromLogger (mc_rtc::Logger &) override
 
void addToGUI (mc_rtc::gui::StateBuilder &) override
 
void configure_ (mc_solver::QPSolver &solver)
 Actual configuration of the stabilizer. Called when reconfigure_ is true. More...
 
void disable_ ()
 
void checkConfiguration (const StabilizerConfiguration &config)
 

Additional Inherited Members

- Public Types inherited from mc_tasks::MetaTask
using Backend = mc_solver::QPSolver::Backend
 
- Protected Member Functions inherited from mc_tasks::MetaTask
virtual std::function< bool(const mc_tasks::MetaTask &task, std::string &)> buildCompletionCriteria (double dt, const mc_rtc::Configuration &config) const
 
- Static Protected Member Functions inherited from mc_tasks::MetaTask
static void addToSolver (MetaTask &t, mc_solver::QPSolver &solver)
 
static void removeFromSolver (MetaTask &t, mc_solver::QPSolver &solver)
 
static void update (MetaTask &t, mc_solver::QPSolver &solver)
 
static void addToLogger (MetaTask &t, mc_rtc::Logger &logger)
 
static void removeFromLogger (MetaTask &t, mc_rtc::Logger &logger)
 
static void addToGUI (MetaTask &t, mc_rtc::gui::StateBuilder &gui)
 
static void removeFromGUI (MetaTask &t, mc_rtc::gui::StateBuilder &gui)
 
static void ensureHasJoints (const mc_rbdyn::Robot &robot, const std::vector< std::string > &joints, const std::string &prefix)
 

Detailed Description

Walking stabilization based on linear inverted pendulum tracking.

Stabilization bridges the gap between the open-loop behavior of the pendulum state reference (feedforward controls) and feedback read from state estimation. In our case, feedback is done on the DCM of the LIPM:

\[ \dot{\xi} = \dot{\xi}^{d} + k_p (\xi^d - \xi) + k_i \int (\xi^d - \xi) \]

Which boils down into corresponding formulas for the CoP and CoM acceleration targets.

Constructor & Destructor Documentation

◆ StabilizerTask() [1/2]

mc_tasks::lipm_stabilizer::StabilizerTask::StabilizerTask ( const mc_rbdyn::Robots robots,
const mc_rbdyn::Robots realRobots,
unsigned int  robotIndex,
const std::string &  leftSurface,
const std::string &  rightSurface,
const std::string &  torsoBodyName,
double  dt 
)

Creates a stabilizer meta task.

Parameters
robotsRobots on which the task acts
realRobotsCorresponding real robot instances
robotIndexIndex of the robot to stabilize
leftSurfaceLeft foot surface name. Its origin should be the center of the foot sole
rightSurfaceLeft foot surface name. Its origin should be the center of the foot sole
torsoBodyNameBody name of the robot's torso (i.e a link above the floating base)
dtController's timestep

◆ StabilizerTask() [2/2]

mc_tasks::lipm_stabilizer::StabilizerTask::StabilizerTask ( const mc_rbdyn::Robots robots,
const mc_rbdyn::Robots realRobots,
unsigned int  robotIndex,
double  dt 
)

Creates a stabilizer meta task.

This constructor uses the stabilizer configuration in the robot module associated to the controlled robot. The stabilizer is started with two feet contacts.

Parameters
robotsRobots on which the task acts
realRobotsCorresponding real robots instance
robotIndexIndex of the robot
dtController's timestep

Member Function Documentation

◆ addToGUI()

void mc_tasks::lipm_stabilizer::StabilizerTask::addToGUI ( mc_rtc::gui::StateBuilder )
overrideprotectedvirtual

Contacts to add to the QPSolver when the task is inserted

Reimplemented from mc_tasks::MetaTask.

◆ addToLogger()

void mc_tasks::lipm_stabilizer::StabilizerTask::addToLogger ( mc_rtc::Logger )
overrideprotectedvirtual

Log stabilizer entries.

Parameters
loggerLogger.

Reimplemented from mc_tasks::MetaTask.

◆ addToSolver()

void mc_tasks::lipm_stabilizer::StabilizerTask::addToSolver ( mc_solver::QPSolver solver)
overrideprotectedvirtual

Contacts to add to the QPSolver when the task is inserted

Implements mc_tasks::MetaTask.

◆ anchorFrame()

sva::PTransformd mc_tasks::lipm_stabilizer::StabilizerTask::anchorFrame ( const mc_rbdyn::Robot robot) const

computes the anchorFrame compatible with the state observers (e.g KinematicInertial)

Parameters
robotRobot from which the frame will be computed
Returns
Anchor frame in-between the feet according to leftFootRatio()

◆ biasDCM()

const Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::biasDCM ( )
inlinenoexcept

◆ checkConfiguration()

void mc_tasks::lipm_stabilizer::StabilizerTask::checkConfiguration ( const StabilizerConfiguration config)
protected

Ensures that the configuration is valid

◆ commitConfig()

void mc_tasks::lipm_stabilizer::StabilizerTask::commitConfig ( )

Use the current configuration as the new default.

◆ commitedConfig()

const StabilizerConfiguration& mc_tasks::lipm_stabilizer::StabilizerTask::commitedConfig ( ) const

Get last commited configuration.

Commited configuration is corresponds to the latest one set by calling commitConfig(), either manually or from the GUI.

See also
config()

◆ comOffsetDerivatorTimeConstant()

void mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetDerivatorTimeConstant ( double  timeConstant)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ comOffsetLowPassCoMCutoffPeriod()

void mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPassCoMCutoffPeriod ( double  cutoffPeriod)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ comOffsetLowPassCutoffPeriod()

void mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPassCutoffPeriod ( double  cutoffPeriod)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ comOffsetMeasured()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetMeasured ( ) const
inlinenoexcept

◆ comOffsetTarget()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetTarget ( )
inlinenoexcept

◆ comStiffness()

void mc_tasks::lipm_stabilizer::StabilizerTask::comStiffness ( const Eigen::Vector3d &  stiffness)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ comWeight()

void mc_tasks::lipm_stabilizer::StabilizerTask::comWeight ( double  weight)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ config()

const StabilizerConfiguration& mc_tasks::lipm_stabilizer::StabilizerTask::config ( ) const

Get current stabilizer's configuration (including changes from GUI/code)

See also
commitedConfig()

◆ configure()

void mc_tasks::lipm_stabilizer::StabilizerTask::configure ( const StabilizerConfiguration config)

Configure stabilizer's parameters from a stabilizer's configuration object

Parameters
configStabilizer configuration. Default values can be found in the RobotModule, and modified from YAML configuration or manually.
See also
load(mc_solver::QPSolver &, const mc_rtc::Configuration &) to set stabilizer targets and contacts from configuration

◆ configure_()

void mc_tasks::lipm_stabilizer::StabilizerTask::configure_ ( mc_solver::QPSolver solver)
protected

Actual configuration of the stabilizer. Called when reconfigure_ is true.

Parameters
solverSolver to which this task has been added

◆ contactAnklePose()

const sva::PTransformd& mc_tasks::lipm_stabilizer::StabilizerTask::contactAnklePose ( ContactState  s) const
inline

Projected pose of the ankle frame in the contact frame.

Parameters
sContact for which the frame is requested
Returns
The projected ankle frame expressed in world frame.

◆ contactDamping()

void mc_tasks::lipm_stabilizer::StabilizerTask::contactDamping ( const sva::MotionVecd &  damping)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ contactStiffness()

void mc_tasks::lipm_stabilizer::StabilizerTask::contactStiffness ( const sva::MotionVecd &  stiffness)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ contactWeight()

void mc_tasks::lipm_stabilizer::StabilizerTask::contactWeight ( double  weight)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ copAdmittance()

void mc_tasks::lipm_stabilizer::StabilizerTask::copAdmittance ( const Eigen::Vector2d &  copAdmittance)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ copMaxVel()

void mc_tasks::lipm_stabilizer::StabilizerTask::copMaxVel ( const sva::MotionVecd &  copMaxVel)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ copVelFilterGain() [1/2]

double mc_tasks::lipm_stabilizer::StabilizerTask::copVelFilterGain ( ) const
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ copVelFilterGain() [2/2]

void mc_tasks::lipm_stabilizer::StabilizerTask::copVelFilterGain ( double  gain)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dcmBiasEstimatorConfiguration() [1/2]

const DCMBiasEstimatorConfiguration& mc_tasks::lipm_stabilizer::StabilizerTask::dcmBiasEstimatorConfiguration ( ) const
inlinenoexcept

Get parameters of the DCM bias estimator.

◆ dcmBiasEstimatorConfiguration() [2/2]

void mc_tasks::lipm_stabilizer::StabilizerTask::dcmBiasEstimatorConfiguration ( const DCMBiasEstimatorConfiguration biasConfig)
inlinenoexcept

Changes the parameters of the DCM bias estimator.

Parameters
biasConfigConfiguration parameters for the bias estimation

◆ dcmDerivatorCutoffPeriod()

void mc_tasks::lipm_stabilizer::StabilizerTask::dcmDerivatorCutoffPeriod ( double  T)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dcmDerivatorTimeConstant()

MC_RTC_DEPRECATED void mc_tasks::lipm_stabilizer::StabilizerTask::dcmDerivatorTimeConstant ( double  T)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dcmGains() [1/2]

void mc_tasks::lipm_stabilizer::StabilizerTask::dcmGains ( const Eigen::Vector2d &  p,
const Eigen::Vector2d &  i,
const Eigen::Vector2d &  d 
)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dcmGains() [2/2]

void mc_tasks::lipm_stabilizer::StabilizerTask::dcmGains ( double  p,
double  i,
double  d 
)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dcmIntegratorTimeConstant()

void mc_tasks::lipm_stabilizer::StabilizerTask::dcmIntegratorTimeConstant ( double  dcmIntegratorTimeConstant)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dfAdmittance()

void mc_tasks::lipm_stabilizer::StabilizerTask::dfAdmittance ( Eigen::Vector3d  dfAdmittance)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ dfDamping()

void mc_tasks::lipm_stabilizer::StabilizerTask::dfDamping ( Eigen::Vector3d  dfDamping)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ disable()

void mc_tasks::lipm_stabilizer::StabilizerTask::disable ( )

Disable all feedback components.

◆ disable_()

void mc_tasks::lipm_stabilizer::StabilizerTask::disable_ ( )
protected

Contacts to add to the QPSolver when the task is inserted

◆ distribZMP()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::distribZMP ( ) const
inlinenoexcept

◆ enable()

void mc_tasks::lipm_stabilizer::StabilizerTask::enable ( )

Enables stabilizer.

This will reinitialize all integrators, and set the stabilizer gains according to the last call to configure()

◆ eval()

Eigen::VectorXd mc_tasks::lipm_stabilizer::StabilizerTask::eval ( ) const
overridevirtual

Returns the task error.

Since the StabilizerTask is a MetaTask, the vector is a concatenation of each sub-tasks. The vector's dimensions depend on the underlying task, and the sub-tasks evaluation depends on their order of insertion.

Implements mc_tasks::MetaTask.

◆ externalWrenchConfiguration() [1/2]

const ExternalWrenchConfiguration& mc_tasks::lipm_stabilizer::StabilizerTask::externalWrenchConfiguration ( ) const
inlinenoexcept

Get the parameters for the external wrenches.

◆ externalWrenchConfiguration() [2/2]

void mc_tasks::lipm_stabilizer::StabilizerTask::externalWrenchConfiguration ( const ExternalWrenchConfiguration extWrenchConfig)
inlinenoexcept

Changes the parameters for the external wrenches.

Parameters
extWrenchConfigConfiguration parameters for the external wrenches

◆ externalWrenches()

const std::vector<ExternalWrench>& mc_tasks::lipm_stabilizer::StabilizerTask::externalWrenches ( ) const
inlinenoexcept

◆ extWrenchSumLowPassCutoffPeriod()

void mc_tasks::lipm_stabilizer::StabilizerTask::extWrenchSumLowPassCutoffPeriod ( double  cutoffPeriod)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ fdqpWeights()

void mc_tasks::lipm_stabilizer::StabilizerTask::fdqpWeights ( const FDQPWeights fdqp)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ filteredDCM()

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::filteredDCM ( ) const
inlinenoexcept

◆ footSurface()

const std::string& mc_tasks::lipm_stabilizer::StabilizerTask::footSurface ( ContactState  s) const
inline

◆ horizonReference()

void mc_tasks::lipm_stabilizer::StabilizerTask::horizonReference ( const std::vector< Eigen::Vector2d > &  ref,
const double  delta 
)
inlinenoexcept

Set the reference zmp sequence to distribute between the CoP task (Only in double support)

It is advised to provide the future support foot name when using this method using the supportFoot method

Parameters
refReference zmp sequence
deltaSequence sampling time

◆ inContact()

bool mc_tasks::lipm_stabilizer::StabilizerTask::inContact ( ContactState  state) const
inlinenoexcept

◆ inDoubleSupport()

bool mc_tasks::lipm_stabilizer::StabilizerTask::inDoubleSupport ( ) const
inlinenoexcept

◆ leftFootRatio()

double mc_tasks::lipm_stabilizer::StabilizerTask::leftFootRatio ( ) const
inlinenoexcept

Interpolation paremeter between left and right foot.

Returns
Left foot ratio between [0,1]

◆ load()

void mc_tasks::lipm_stabilizer::StabilizerTask::load ( mc_solver::QPSolver ,
const mc_rtc::Configuration config 
)
overridevirtual

Load targets and contacts from configuration.

Reimplemented from mc_tasks::MetaTask.

◆ measuredCoM()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoM ( )
inlinenoexcept

◆ measuredCoMd()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoMd ( )
inlinenoexcept

◆ measuredDCM()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::measuredDCM ( )
inlinenoexcept

◆ measuredFilteredNetForces()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::measuredFilteredNetForces ( ) const
inlinenoexcept

◆ measuredZMP()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::measuredZMP ( )
inlinenoexcept

◆ name() [1/3]

const std::string& mc_tasks::MetaTask::name
inline

Get the name of the task

◆ name() [2/3]

virtual void mc_tasks::MetaTask::name
inline

Set a name for the task

This name will be used to identify the task in logs, GUI...

The name should be set before being added to the solver.

◆ name() [3/3]

void mc_tasks::lipm_stabilizer::StabilizerTask::name ( const std::string &  name)
inlineoverridevirtual

Set a name for the task

This name will be used to identify the task in logs, GUI...

The name should be set before being added to the solver.

Reimplemented from mc_tasks::MetaTask.

◆ omega()

double mc_tasks::lipm_stabilizer::StabilizerTask::omega ( ) const
inline

Contacts to add to the QPSolver when the task is inserted

◆ pelvisStiffness()

void mc_tasks::lipm_stabilizer::StabilizerTask::pelvisStiffness ( double  stiffness)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ pelvisWeight()

void mc_tasks::lipm_stabilizer::StabilizerTask::pelvisWeight ( double  weight)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ realRobot()

const mc_rbdyn::Robot& mc_tasks::lipm_stabilizer::StabilizerTask::realRobot ( ) const
inlinenoexcept

◆ reconfigure()

void mc_tasks::lipm_stabilizer::StabilizerTask::reconfigure ( )

Reset stabilizer configuration from last configuration set by configure()

Does not include changes made from the GUI.

◆ removeFromGUI()

void mc_tasks::lipm_stabilizer::StabilizerTask::removeFromGUI ( mc_rtc::gui::StateBuilder )
overrideprotectedvirtual

Contacts to add to the QPSolver when the task is inserted

Reimplemented from mc_tasks::MetaTask.

◆ removeFromLogger()

void mc_tasks::lipm_stabilizer::StabilizerTask::removeFromLogger ( mc_rtc::Logger )
overrideprotectedvirtual

Contacts to add to the QPSolver when the task is inserted

Reimplemented from mc_tasks::MetaTask.

◆ removeFromSolver()

void mc_tasks::lipm_stabilizer::StabilizerTask::removeFromSolver ( mc_solver::QPSolver solver)
overrideprotectedvirtual

Contacts to add to the QPSolver when the task is inserted

Implements mc_tasks::MetaTask.

◆ reset()

void mc_tasks::lipm_stabilizer::StabilizerTask::reset ( )
overridevirtual

Resets the stabilizer tasks and parameters to their default configuration.

Resets all tasks and errors/integrator/derivators to their initial configuration. Configures the default stabilizer parameters from the robot module.

You can configure the stabilizer parameters (DCM tacking gains, task gains, etc) by calling configure(const StabilizerConfiguration & config)

Note
If you wish to reset the stabilizer from it's current configuration, you can do so by storing its current configuration as accessed by config() or commitedConfig() and set it explitely after calling reset by calling configure(const StabilizerConfiguration &);

Implements mc_tasks::MetaTask.

◆ robot()

const mc_rbdyn::Robot& mc_tasks::lipm_stabilizer::StabilizerTask::robot ( ) const
inlinenoexcept

◆ run()

void mc_tasks::lipm_stabilizer::StabilizerTask::run ( )

Update QP task targets.

This function is called once the reference has been updated.

◆ safetyThresholds()

void mc_tasks::lipm_stabilizer::StabilizerTask::safetyThresholds ( const SafetyThresholds thresholds)
inlinenoexcept

Changes the safety thresholds.

This ensures that all the parameters depending on these safety parameters are within the new thresholds. If they are out of bounds, they will be clamped back to the new range, and a warning message will be displayed.

Parameters
thresholdsNew safety thresholds

◆ setContacts() [1/3]

void mc_tasks::lipm_stabilizer::StabilizerTask::setContacts ( const ContactDescriptionVector contacts)

Configure foot tasks for contact at a given location, and add contacts to the solver.

Note
To use the stabilizer with dynamics constraint, you need to add the corresponding mc_rbdyn::Contact to the solver and free the roll/pitch rotation and z translation (in contact frame). This assumes the foot surfaces to have x pointing towards the front of the foot, and z from the ground up.
Parameters
solverThe QP solver to which the contact tasks will be added. Note that this method will not add contact constraints to the QPSolver. If you wish to do so, bear in mind that for the stabilizer to work properly, the contact's dofs along the x and y rotations and z translation need to be free.

◆ setContacts() [2/3]

void mc_tasks::lipm_stabilizer::StabilizerTask::setContacts ( const std::vector< ContactState > &  contacts)

Helper to set contacts from the current surface pose

Parameters
contactsContacts to add. Their pose will be determined set from the realRobot estimate of the foot surface pose. Use with caution.
See also
void setContacts(mc_solver::QPSolver &, const std::vector<std::pair<ContactState, sva::PTransformd>> &);

◆ setContacts() [3/3]

void mc_tasks::lipm_stabilizer::StabilizerTask::setContacts ( const std::vector< std::pair< ContactState, sva::PTransformd >> &  contacts)

Helper to set contacts with a provided target pose.

Parameters
contactsvectors of contacts defined by their ContactState and a desired pose

◆ setExternalWrenches()

void mc_tasks::lipm_stabilizer::StabilizerTask::setExternalWrenches ( const std::vector< std::string > &  surfaceNames,
const std::vector< sva::ForceVecd > &  targetWrenches,
const std::vector< sva::MotionVecd > &  gains 
)

Set the wrench that the robot expects to receive from the external contacts.

Change the configurations in ExternalWrenchConfiguration to handle external wrenches because external wrenches are ignored by default.

See also
ExternalWrenchConfiguration
Parameters
surfaceNamesNames of the surface to which the external wrench is applied
targetWrenchesTarget (expected) external wrenches
gainsGains of measured external wrenches

◆ speed()

Eigen::VectorXd mc_tasks::lipm_stabilizer::StabilizerTask::speed ( ) const
overridevirtual

Returns the task velocity.

Since the StabilizerTask is a MetaTask, the vector is a concatenation of each sub-tasks. The vector's dimensions depend on the underlying task, and the sub-tasks evaluation depends on their order of insertion.

Implements mc_tasks::MetaTask.

◆ staticTarget()

void mc_tasks::lipm_stabilizer::StabilizerTask::staticTarget ( const Eigen::Vector3d &  com,
double  zmpHeight = 0 
)

Provides a static target to the stabilizer.

  • CoM target : user-provided
  • CoM velocity target: zero (static)
  • CoM acceleration target: zero (static)
  • ZMP: computed under the CoM
Parameters
comdesired com position
zmpHeight[=0]optional height of the ZMP plane (eg contacts), used to compute the pendulums omega.
See also
target for dynamic motions.

◆ supportFoot() [1/2]

ContactState mc_tasks::lipm_stabilizer::StabilizerTask::supportFoot ( ) const
inlinenoexcept

◆ supportFoot() [2/2]

void mc_tasks::lipm_stabilizer::StabilizerTask::supportFoot ( const ContactState &  foot)
inlinenoexcept

◆ target()

void mc_tasks::lipm_stabilizer::StabilizerTask::target ( const Eigen::Vector3d &  com,
const Eigen::Vector3d &  comd,
const Eigen::Vector3d &  comdd,
const Eigen::Vector3d &  zmp,
const Eigen::Vector3d &  zmpd = Eigen::Vector3d::Zero() 
)

Provides a dynamic target to the stabilizer.

Note that this target should be updated at each iteration and provide a dynamically-consistent trajectory. This would typically be generated by a compatible Model Preview Controller.

See https://github.com/jrl-umi3218/lipm_walking_controller for example in the context of walking.

Parameters
comDesired CoM position
comdDesired CoM velocity
comddDesired CoM acceleration
zmpDesired ZMP
zmpdDesired ZMP velocity (can be omitted when zmpdGain in StabilizerConfiguration is zero)
See also
staticTarget for a helper to define the stabilizer target when the CoM is static

◆ targetCoM()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::targetCoM ( ) const
inlinenoexcept

Returns the CoM target used for stabilization.

The stabilizer may modify the user-provided target targetCoMRaw() to compensate for external forces and/or bias. The target returned by this function thus corresponds to the actual target used by the stabilizer, and not the raw user provided target.

◆ targetCoMAcceleration()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::targetCoMAcceleration ( ) const
inlinenoexcept

◆ targetCoMRaw()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::targetCoMRaw ( ) const
inlinenoexcept

Return the raw CoM target as provided by target().

Warning
: Depending on the stabilizer configuration, this target may be modified by the stabilizer (to take into account bias and external forces).
See also
targetCoM()

◆ targetCoMVelocity()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::targetCoMVelocity ( ) const
inlinenoexcept

◆ targetZMP()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::targetZMP ( ) const
inlinenoexcept

◆ targetZMPVelocity()

const Eigen::Vector3d& mc_tasks::lipm_stabilizer::StabilizerTask::targetZMPVelocity ( ) const
inlinenoexcept

◆ torsoPitch()

void mc_tasks::lipm_stabilizer::StabilizerTask::torsoPitch ( double  pitch)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ torsoStiffness()

void mc_tasks::lipm_stabilizer::StabilizerTask::torsoStiffness ( double  stiffness)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ torsoWeight()

void mc_tasks::lipm_stabilizer::StabilizerTask::torsoWeight ( double  weight)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ update()

void mc_tasks::lipm_stabilizer::StabilizerTask::update ( mc_solver::QPSolver )
overrideprotectedvirtual

Contacts to add to the QPSolver when the task is inserted

Implements mc_tasks::MetaTask.

◆ vdcFrequency()

void mc_tasks::lipm_stabilizer::StabilizerTask::vdcFrequency ( double  freq)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ vdcStiffness()

void mc_tasks::lipm_stabilizer::StabilizerTask::vdcStiffness ( double  stiffness)
inlinenoexcept

Contacts to add to the QPSolver when the task is inserted

◆ zmpCoeffMeasured()

double mc_tasks::lipm_stabilizer::StabilizerTask::zmpCoeffMeasured ( ) const
inlinenoexcept

Member Data Documentation

◆ addContacts_

std::vector<ContactState> mc_tasks::lipm_stabilizer::StabilizerTask::addContacts_
protected

Contacts to add to the QPSolver when the task is inserted

◆ c_

StabilizerConfiguration mc_tasks::lipm_stabilizer::StabilizerTask::c_
protected

Whether the stabilizer needs to be reconfigured at the next update(solver) call

◆ comddTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comddTarget_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ comdTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comdTarget_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ comOffsetDerivator_

mc_filter::StationaryOffset<Eigen::Vector3d> mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetDerivator_
protected

Derivator of CoM offset

◆ comOffsetErr_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetErr_ = Eigen::Vector3d::Zero()
protected

CoM offset error

◆ comOffsetErrCoM_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetErrCoM_ = Eigen::Vector3d::Zero()
protected

CoM offset error handled by CoM modification

◆ comOffsetErrZMP_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetErrZMP_ = Eigen::Vector3d::Zero()
protected

CoM offset error handled by ZMP modification

◆ comOffsetLowPass_

mc_filter::LowPass<Eigen::Vector3d> mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPass_
protected

Low-pass filter of CoM offset

◆ comOffsetLowPassCoM_

mc_filter::LowPass<Eigen::Vector3d> mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPassCoM_
protected

Low-pass filter of CoM offset to extract CoM modification

◆ comOffsetMeasured_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetMeasured_ = Eigen::Vector3d::Zero()
protected

Measured CoM offset

◆ comOffsetTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetTarget_ = Eigen::Vector3d::Zero()
protected

Target (expected) CoM offset

◆ comTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comTarget_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ comTargetRaw_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::comTargetRaw_ = Eigen::Vector3d::Zero()
protected

Stabilizer targets

◆ comTask

std::shared_ptr<mc_tasks::CoMTask> mc_tasks::lipm_stabilizer::StabilizerTask::comTask
protected

Contacts to add to the QPSolver when the task is inserted

◆ contacts_

std::unordered_map<ContactState, internal::Contact, EnumClassHash, std::equal_to<ContactState>, Eigen::aligned_allocator<std::pair<const ContactState, internal::Contact> > > mc_tasks::lipm_stabilizer::StabilizerTask::contacts_
protected

Contacts to add to the QPSolver when the task is inserted

◆ contactSensors

std::vector<std::string> mc_tasks::lipm_stabilizer::StabilizerTask::contactSensors
protected

Foot tasks for the established contacts

◆ contactTasks

std::vector<std::shared_ptr<mc_tasks::force::CoPTask> > mc_tasks::lipm_stabilizer::StabilizerTask::contactTasks
protected

Contacts to add to the QPSolver when the task is inserted

◆ dcmAverageError_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::dcmAverageError_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ dcmDerivator_

mc_filter::LowPassCompose<Eigen::Vector3d> mc_tasks::lipm_stabilizer::StabilizerTask::dcmDerivator_
protected

◆ dcmError_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::dcmError_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ dcmEstimator_

stateObservation::LipmDcmEstimator mc_tasks::lipm_stabilizer::StabilizerTask::dcmEstimator_
protected

Filtering of the divergent component of motion (DCM) and estimation of a bias betweeen the DCM and the corresponding zero moment point for a linearized inverted pendulum model. Whether the estimator needs to be reset (robot in the air, initialization)

◆ dcmEstimatorNeedsReset_

bool mc_tasks::lipm_stabilizer::StabilizerTask::dcmEstimatorNeedsReset_ = true
protected

Contacts to add to the QPSolver when the task is inserted

◆ dcmIntegrator_

mc_filter::ExponentialMovingAverage<Eigen::Vector3d> mc_tasks::lipm_stabilizer::StabilizerTask::dcmIntegrator_
protected

◆ dcmTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::dcmTarget_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ dcmVelError_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::dcmVelError_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ defaultConfig_

StabilizerConfiguration mc_tasks::lipm_stabilizer::StabilizerTask::defaultConfig_
protected

< Default (user-provided) configuration for the stabilizer. This configuration is superseeded by the parameters set in the GUI Last valid stabilizer configuration.

◆ delayedTargetCoPLeft_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::delayedTargetCoPLeft_ = Eigen::Vector2d::Zero()
protected

Considered target for the delay

◆ delayedTargetCoPRight_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::delayedTargetCoPRight_ = Eigen::Vector2d::Zero()
protected

Considered target for the delay

◆ delayedTargetFzLeft_

double mc_tasks::lipm_stabilizer::StabilizerTask::delayedTargetFzLeft_ = 0
protected

Considered target for the delay

◆ delayedTargetFzRight_

double mc_tasks::lipm_stabilizer::StabilizerTask::delayedTargetFzRight_ = 0
protected

Considered target for the delay

◆ desiredFzLeft_

double mc_tasks::lipm_stabilizer::StabilizerTask::desiredFzLeft_ = 0.
protected

Used for logging

◆ desiredFzRight_

double mc_tasks::lipm_stabilizer::StabilizerTask::desiredFzRight_ = 0.
protected

Used for logging

◆ desiredWrench_

sva::ForceVecd mc_tasks::lipm_stabilizer::StabilizerTask::desiredWrench_ = sva::ForceVecd::Zero()
protected

Result of the DCM feedback

◆ dfError_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::dfError_ = Eigen::Vector3d::Zero()
protected

Height error in foot force difference control

◆ dfForceError_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::dfForceError_ = Eigen::Vector3d::Zero()
protected

Force error in foot force difference control

◆ disableConfig_

StabilizerConfiguration mc_tasks::lipm_stabilizer::StabilizerTask::disableConfig_
protected

Online stabilizer configuration, can be set from the GUI. Defaults to defaultConfig_

◆ distribCheck_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::distribCheck_ = Eigen::Vector2d::Zero()
protected

◆ distribWrench_

sva::ForceVecd mc_tasks::lipm_stabilizer::StabilizerTask::distribWrench_ = sva::ForceVecd::Zero()
protected

Result of the force distribution QP

◆ distribZMP_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::distribZMP_
protected
Initial value:
=
Eigen::Vector3d::Zero()

ZMP corresponding to force distribution result (desired ZMP)

◆ dt_

double mc_tasks::lipm_stabilizer::StabilizerTask::dt_ = 0.005
protected

Controller cycle in [s]

◆ enabled_

bool mc_tasks::lipm_stabilizer::StabilizerTask::enabled_ = true
protected

Contacts to add to the QPSolver when the task is inserted

◆ extWrenches_

std::vector<ExternalWrench> mc_tasks::lipm_stabilizer::StabilizerTask::extWrenches_
protected

Sum of target (expected) external wrenches

◆ extWrenchSumLowPass_

mc_filter::LowPass<sva::ForceVecd> mc_tasks::lipm_stabilizer::StabilizerTask::extWrenchSumLowPass_
protected

Low-pass filter of the sum of the measured external wrenches

◆ extWrenchSumMeasured_

sva::ForceVecd mc_tasks::lipm_stabilizer::StabilizerTask::extWrenchSumMeasured_ = sva::ForceVecd::Zero()
protected

Sum of measured external wrenches

◆ extWrenchSumTarget_

sva::ForceVecd mc_tasks::lipm_stabilizer::StabilizerTask::extWrenchSumTarget_ = sva::ForceVecd::Zero()
protected

Sum of target (expected) external wrenches

◆ footTasks

std::unordered_map<ContactState, std::shared_ptr<mc_tasks::force::CoPTask>, EnumClassHash> mc_tasks::lipm_stabilizer::StabilizerTask::footTasks
protected

Contacts to add to the QPSolver when the task is inserted

◆ fSumFilter_

mc_filter::LowPass<Eigen::Vector3d> mc_tasks::lipm_stabilizer::StabilizerTask::fSumFilter_
protected

Low pass filter that sum the forces on both feet>

◆ horizonCoPDistribution_

bool mc_tasks::lipm_stabilizer::StabilizerTask::horizonCoPDistribution_ = false
protected

◆ horizonDelta_

double mc_tasks::lipm_stabilizer::StabilizerTask::horizonDelta_ = 0.05
protected

Sequence sampling period Is set to true when a new zmp sequence is provided and overided classical distribution

◆ horizonRefUpdated_

bool mc_tasks::lipm_stabilizer::StabilizerTask::horizonRefUpdated_ = false
protected

◆ horizonZmpRef_

std::vector<Eigen::Vector2d> mc_tasks::lipm_stabilizer::StabilizerTask::horizonZmpRef_
protected

Future ZMP reference during tHorizon

◆ inTheAir_

bool mc_tasks::lipm_stabilizer::StabilizerTask::inTheAir_ = false
protected

Is the robot in the air?

◆ lastConfig_

StabilizerConfiguration mc_tasks::lipm_stabilizer::StabilizerTask::lastConfig_
protected

Stabilizer configuration to disable.

◆ leftFootRatio_

double mc_tasks::lipm_stabilizer::StabilizerTask::leftFootRatio_ = 0.5
protected

Weight distribution ratio (0: all weight on right foot, 1: all on left foot)

◆ mass_

double mc_tasks::lipm_stabilizer::StabilizerTask::mass_ = 38.
protected

Robot mass in [kg]

◆ measuredCoM_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoM_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ measuredCoMd_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoMd_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ measuredCoMdd_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoMdd_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ measuredCoMUnbiased_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoMUnbiased_ = Eigen::Vector3d::Zero()
protected

DCM unbiased (only used for logging)

◆ measuredDCM_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredDCM_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ measuredDCMUnbiased_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredDCMUnbiased_ = Eigen::Vector3d::Zero()
protected

Measured DCM (only used for logging)

◆ measuredNetWrench_

sva::ForceVecd mc_tasks::lipm_stabilizer::StabilizerTask::measuredNetWrench_ = sva::ForceVecd::Zero()
protected

CoM unbiased (only used for logging)

◆ measuredZMP_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::measuredZMP_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ modeledCoPLeft_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::modeledCoPLeft_ = Eigen::Vector2d::Zero()
protected

Used for logging

◆ modeledCoPRight_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::modeledCoPRight_ = Eigen::Vector2d::Zero()
protected

Used for logging

◆ modeledFzLeft_

double mc_tasks::lipm_stabilizer::StabilizerTask::modeledFzLeft_ = 0.
protected

Used for logging

◆ modeledFzRight_

double mc_tasks::lipm_stabilizer::StabilizerTask::modeledFzRight_ = 0.
protected

Used for logging

◆ omega_

double mc_tasks::lipm_stabilizer::StabilizerTask::omega_ = 3.4
protected

Contacts to add to the QPSolver when the task is inserted

◆ pelvisTask

std::shared_ptr<mc_tasks::OrientationTask> mc_tasks::lipm_stabilizer::StabilizerTask::pelvisTask
protected

Pelvis orientation task

◆ QPCoPLeft_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::QPCoPLeft_
protected
Initial value:
=
Eigen::Vector2d::Zero()

Get the next modeled CoP by the Horizon based force distribution QP

◆ QPCoPRight_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::QPCoPRight_
protected
Initial value:
=
Eigen::Vector2d::Zero()

Get the next modeled CoP by the Horizon based force distribution QP Error between the computed ZMP byt the Horizon based force distribution QP and the reference zmp>

◆ qpSolver_

Eigen::QuadProgDense mc_tasks::lipm_stabilizer::StabilizerTask::qpSolver_
protected

Whether the stabilizer is enabled Least-squares solver for wrench distribution

◆ realRobots_

const mc_rbdyn::Robots& mc_tasks::lipm_stabilizer::StabilizerTask::realRobots_
protected

Contacts to add to the QPSolver when the task is inserted

◆ reconfigure_

bool mc_tasks::lipm_stabilizer::StabilizerTask::reconfigure_ = true
protected

Contacts to add to the QPSolver when the task is inserted

◆ robotIndex_

unsigned int mc_tasks::lipm_stabilizer::StabilizerTask::robotIndex_
protected

Contacts to add to the QPSolver when the task is inserted

◆ robots_

const mc_rbdyn::Robots& mc_tasks::lipm_stabilizer::StabilizerTask::robots_
protected

Contacts to add to the QPSolver when the task is inserted

◆ runTime_

double mc_tasks::lipm_stabilizer::StabilizerTask::runTime_ = 0.
protected

◆ supportFoot_

ContactState mc_tasks::lipm_stabilizer::StabilizerTask::supportFoot_ = ContactState::Left
protected

Future support foot

◆ supportMax_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::supportMax_ = Eigen::Vector2d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ supportMin_

Eigen::Vector2d mc_tasks::lipm_stabilizer::StabilizerTask::supportMin_ = Eigen::Vector2d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ supportPolygons_

std::vector<std::vector<Eigen::Vector3d> > mc_tasks::lipm_stabilizer::StabilizerTask::supportPolygons_
protected

Force sensors corresponding to established contacts For GUI display

◆ t_

double mc_tasks::lipm_stabilizer::StabilizerTask::t_ = 0.
protected

Time elapsed since the task is running

◆ tComputation_

double mc_tasks::lipm_stabilizer::StabilizerTask::tComputation_ = 0.
protected

time when the Horizon based force distribution has been computed

◆ torsoTask

std::shared_ptr<mc_tasks::OrientationTask> mc_tasks::lipm_stabilizer::StabilizerTask::torsoTask
protected

Torso orientation task

◆ vdcHeightError_

double mc_tasks::lipm_stabilizer::StabilizerTask::vdcHeightError_ = 0
protected

Average height error used in vertical drift compensation

◆ wasEnabled_

bool mc_tasks::lipm_stabilizer::StabilizerTask::wasEnabled_ = true
protected

Whether the stabilizer was enabled before the robot was in the air

◆ wasInTheAir_

bool mc_tasks::lipm_stabilizer::StabilizerTask::wasInTheAir_ = false
protected

Whether the robot was in the air at the previous iteration

◆ zmpcc_

ZMPCC mc_tasks::lipm_stabilizer::StabilizerTask::zmpcc_
protected

Compute CoM offset due to ZMPCC compensation

◆ zmpccOnlyDS_

bool mc_tasks::lipm_stabilizer::StabilizerTask::zmpccOnlyDS_ = true
protected

Only apply ZMPCC in double support

◆ zmpCoefMeasured_

double mc_tasks::lipm_stabilizer::StabilizerTask::zmpCoefMeasured_ = 1
protected

Measured Zmp Coefficient

◆ zmpCoefTarget_

double mc_tasks::lipm_stabilizer::StabilizerTask::zmpCoefTarget_ = 1
protected

target (expected) Zmp Coefficient

◆ zmpdTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::zmpdTarget_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted

◆ zmpFrame_

sva::PTransformd mc_tasks::lipm_stabilizer::StabilizerTask::zmpFrame_ = sva::PTransformd::Identity()
protected

Frame in which the ZMP is computed

◆ zmpTarget_

Eigen::Vector3d mc_tasks::lipm_stabilizer::StabilizerTask::zmpTarget_ = Eigen::Vector3d::Zero()
protected

Contacts to add to the QPSolver when the task is inserted


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