#include <mc_tasks/lipm_stabilizer/StabilizerTask.h>
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 StabilizerConfiguration & | config () const |
Get current stabilizer's configuration (including changes from GUI/code) More... | |
const StabilizerConfiguration & | commitedConfig () 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::Robot & | robot () const noexcept |
const mc_rbdyn::Robot & | realRobot () 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< ExternalWrench > | extWrenches_ |
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.
| |
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 >, EnumClassHash > | footTasks |
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::CoMTask > | comTask |
std::shared_ptr< mc_tasks::OrientationTask > | pelvisTask |
std::shared_ptr< mc_tasks::OrientationTask > | torsoTask |
const mc_rbdyn::Robots & | robots_ |
const mc_rbdyn::Robots & | realRobots_ |
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 DCMBiasEstimatorConfiguration & | dcmBiasEstimatorConfiguration () 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 ExternalWrenchConfiguration & | externalWrenchConfiguration () 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) |
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.
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.
robots | Robots on which the task acts |
realRobots | Corresponding real robot instances |
robotIndex | Index of the robot to stabilize |
leftSurface | Left foot surface name. Its origin should be the center of the foot sole |
rightSurface | Left foot surface name. Its origin should be the center of the foot sole |
torsoBodyName | Body name of the robot's torso (i.e a link above the floating base) |
dt | Controller's timestep |
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.
robots | Robots on which the task acts |
realRobots | Corresponding real robots instance |
robotIndex | Index of the robot |
dt | Controller's timestep |
|
overrideprotectedvirtual |
Contacts to add to the QPSolver when the task is inserted
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
|
overrideprotectedvirtual |
Contacts to add to the QPSolver when the task is inserted
Implements mc_tasks::MetaTask.
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)
robot | Robot from which the frame will be computed |
|
inlinenoexcept |
|
protected |
Ensures that the configuration is valid
void mc_tasks::lipm_stabilizer::StabilizerTask::commitConfig | ( | ) |
Use the current configuration as the new default.
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.
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
const StabilizerConfiguration& mc_tasks::lipm_stabilizer::StabilizerTask::config | ( | ) | const |
Get current stabilizer's configuration (including changes from GUI/code)
void mc_tasks::lipm_stabilizer::StabilizerTask::configure | ( | const StabilizerConfiguration & | config | ) |
Configure stabilizer's parameters from a stabilizer's configuration object
config | Stabilizer configuration. Default values can be found in the RobotModule, and modified from YAML configuration or manually. |
|
protected |
Actual configuration of the stabilizer. Called when reconfigure_ is true.
solver | Solver to which this task has been added |
|
inline |
Projected pose of the ankle frame in the contact frame.
s | Contact for which the frame is requested |
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Get parameters of the DCM bias estimator.
|
inlinenoexcept |
Changes the parameters of the DCM bias estimator.
biasConfig | Configuration parameters for the bias estimation |
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
void mc_tasks::lipm_stabilizer::StabilizerTask::disable | ( | ) |
Disable all feedback components.
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
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()
|
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.
|
inlinenoexcept |
Get the parameters for the external wrenches.
|
inlinenoexcept |
Changes the parameters for the external wrenches.
extWrenchConfig | Configuration parameters for the external wrenches |
|
inlinenoexcept |
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
|
inline |
|
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
ref | Reference zmp sequence |
delta | Sequence sampling time |
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
Interpolation paremeter between left and right foot.
|
overridevirtual |
Load targets and contacts from configuration.
Reimplemented from mc_tasks::MetaTask.
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
|
inline |
Get the name of the task
|
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.
|
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.
|
inline |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
void mc_tasks::lipm_stabilizer::StabilizerTask::reconfigure | ( | ) |
Reset stabilizer configuration from last configuration set by configure()
Does not include changes made from the GUI.
|
overrideprotectedvirtual |
Contacts to add to the QPSolver when the task is inserted
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
Contacts to add to the QPSolver when the task is inserted
Reimplemented from mc_tasks::MetaTask.
|
overrideprotectedvirtual |
Contacts to add to the QPSolver when the task is inserted
Implements mc_tasks::MetaTask.
|
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)
Implements mc_tasks::MetaTask.
|
inlinenoexcept |
void mc_tasks::lipm_stabilizer::StabilizerTask::run | ( | ) |
Update QP task targets.
This function is called once the reference has been updated.
|
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.
thresholds | New safety thresholds |
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.
solver | The 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. |
void mc_tasks::lipm_stabilizer::StabilizerTask::setContacts | ( | const std::vector< ContactState > & | contacts | ) |
Helper to set contacts from the current surface pose
contacts | Contacts to add. Their pose will be determined set from the realRobot estimate of the foot surface pose. Use with caution. |
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.
contacts | vectors of contacts defined by their ContactState and a desired pose |
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.
surfaceNames | Names of the surface to which the external wrench is applied |
targetWrenches | Target (expected) external wrenches |
gains | Gains of measured external wrenches |
|
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.
void mc_tasks::lipm_stabilizer::StabilizerTask::staticTarget | ( | const Eigen::Vector3d & | com, |
double | zmpHeight = 0 |
||
) |
Provides a static target to the stabilizer.
com | desired com position |
zmpHeight[=0] | optional height of the ZMP plane (eg contacts), used to compute the pendulums omega. |
|
inlinenoexcept |
|
inlinenoexcept |
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.
com | Desired CoM position |
comd | Desired CoM velocity |
comdd | Desired CoM acceleration |
zmp | Desired ZMP |
zmpd | Desired ZMP velocity (can be omitted when zmpdGain in StabilizerConfiguration is zero) |
|
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.
|
inlinenoexcept |
|
inlinenoexcept |
Return the raw CoM target as provided by target().
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
overrideprotectedvirtual |
Contacts to add to the QPSolver when the task is inserted
Implements mc_tasks::MetaTask.
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
Contacts to add to the QPSolver when the task is inserted
|
inlinenoexcept |
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Whether the stabilizer needs to be reconfigured at the next update(solver) call
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Derivator of CoM offset
|
protected |
CoM offset error
|
protected |
CoM offset error handled by CoM modification
|
protected |
CoM offset error handled by ZMP modification
|
protected |
Low-pass filter of CoM offset
|
protected |
Low-pass filter of CoM offset to extract CoM modification
|
protected |
Measured CoM offset
|
protected |
Target (expected) CoM offset
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Stabilizer targets
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Foot tasks for the established contacts
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
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)
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
< Default (user-provided) configuration for the stabilizer. This configuration is superseeded by the parameters set in the GUI Last valid stabilizer configuration.
|
protected |
Considered target for the delay
|
protected |
Considered target for the delay
|
protected |
Considered target for the delay
|
protected |
Considered target for the delay
|
protected |
Used for logging
|
protected |
Used for logging
|
protected |
Result of the DCM feedback
|
protected |
Height error in foot force difference control
|
protected |
Force error in foot force difference control
|
protected |
Online stabilizer configuration, can be set from the GUI. Defaults to defaultConfig_
|
protected |
|
protected |
Result of the force distribution QP
|
protected |
ZMP corresponding to force distribution result (desired ZMP)
|
protected |
Controller cycle in [s]
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Sum of target (expected) external wrenches
|
protected |
Low-pass filter of the sum of the measured external wrenches
|
protected |
Sum of measured external wrenches
|
protected |
Sum of target (expected) external wrenches
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Low pass filter that sum the forces on both feet>
|
protected |
|
protected |
Sequence sampling period Is set to true when a new zmp sequence is provided and overided classical distribution
|
protected |
|
protected |
Future ZMP reference during tHorizon
|
protected |
Is the robot in the air?
|
protected |
Stabilizer configuration to disable.
|
protected |
Weight distribution ratio (0: all weight on right foot, 1: all on left foot)
|
protected |
Robot mass in [kg]
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
DCM unbiased (only used for logging)
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Measured DCM (only used for logging)
|
protected |
CoM unbiased (only used for logging)
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Used for logging
|
protected |
Used for logging
|
protected |
Used for logging
|
protected |
Used for logging
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Pelvis orientation task
|
protected |
Get the next modeled CoP by the Horizon based force distribution QP
|
protected |
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>
|
protected |
Whether the stabilizer is enabled Least-squares solver for wrench distribution
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
|
protected |
Future support foot
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Force sensors corresponding to established contacts For GUI display
|
protected |
Time elapsed since the task is running
|
protected |
time when the Horizon based force distribution has been computed
|
protected |
Torso orientation task
|
protected |
Average height error used in vertical drift compensation
|
protected |
Whether the stabilizer was enabled before the robot was in the air
|
protected |
Whether the robot was in the air at the previous iteration
|
protected |
Compute CoM offset due to ZMPCC compensation
|
protected |
Only apply ZMPCC in double support
|
protected |
Measured Zmp Coefficient
|
protected |
target (expected) Zmp Coefficient
|
protected |
Contacts to add to the QPSolver when the task is inserted
|
protected |
Frame in which the ZMP is computed
|
protected |
Contacts to add to the QPSolver when the task is inserted