Go to the documentation of this file.
24 #include <state-observation/dynamics-estimators/lipm-dcm-estimator.hpp>
27 #include <eigen-quadprog/QuadProg.h>
32 namespace lipm_stabilizer
58 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
88 unsigned int robotIndex,
89 const std::string & leftSurface,
90 const std::string & rightSurface,
91 const std::string & torsoBodyName,
110 unsigned int robotIndex,
113 inline void name(
const std::string & name)
override
120 const auto n = name_ +
"_Tasks";
121 comTask->name(n +
"_com");
123 footTasks.at(ContactState::Right)->name(n +
"_cop_right");
124 pelvisTask->name(n +
"_pelvis");
125 torsoTask->name(n +
"_torso");
145 void reset()
override;
153 Eigen::VectorXd eval()
const override;
161 Eigen::VectorXd speed()
const override;
243 void setContacts(
const std::vector<std::pair<ContactState, sva::PTransformd>> & contacts);
252 void setContacts(
const std::vector<ContactState> & contacts);
261 inline const sva::PTransformd &
contactAnklePose(ContactState s)
const {
return contacts_.at(s).anklePose(); }
263 inline const std::string &
footSurface(ContactState s)
const {
return footTasks.at(s)->surface(); }
295 void staticTarget(
const Eigen::Vector3d & com,
double zmpHeight = 0);
317 void target(
const Eigen::Vector3d & com,
318 const Eigen::Vector3d & comd,
319 const Eigen::Vector3d & comdd,
320 const Eigen::Vector3d &
zmp,
321 const Eigen::Vector3d & zmpd = Eigen::Vector3d::Zero());
330 inline const Eigen::Vector3d &
targetCoMRaw() const noexcept {
return comTargetRaw_; }
339 inline const Eigen::Vector3d &
targetCoM() const noexcept {
return comTargetRaw_; }
348 inline const Eigen::Vector3d &
targetZMP() const noexcept {
return zmpTarget_; }
354 inline ContactState
supportFoot() const noexcept {
return supportFoot_; }
357 inline void supportFoot(
const ContactState & foot) noexcept { supportFoot_ = foot; }
368 inline void horizonReference(
const std::vector<Eigen::Vector2d> & ref,
const double delta) noexcept
370 horizonZmpRef_ = ref;
371 horizonDelta_ = delta;
372 horizonCoPDistribution_ =
true;
373 horizonRefUpdated_ =
true;
388 void setExternalWrenches(
const std::vector<std::string> & surfaceNames,
389 const std::vector<sva::ForceVecd> & targetWrenches,
390 const std::vector<sva::MotionVecd> & gains);
396 inline const std::vector<ExternalWrench> &
externalWrenches() const noexcept {
return extWrenches_; }
401 inline const Eigen::Vector3d &
distribZMP() const noexcept {
return distribZMP_; }
403 inline const Eigen::Vector3d &
measuredDCM() noexcept {
return measuredDCM_; }
405 inline const Eigen::Vector2d
biasDCM() noexcept
407 if(c_.dcmBias.withDCMBias) {
return dcmEstimator_.getBias(); }
408 return Eigen::Vector2d::Zero();
413 if(c_.dcmBias.withDCMBias) {
return dcmEstimator_.getUnbiasedDCM(); }
414 return measuredDCM_.segment(0, 2);
417 inline const Eigen::Vector3d &
measuredZMP() noexcept {
return measuredZMP_; }
419 inline const Eigen::Vector3d &
measuredCoM() noexcept {
return measuredCoM_; }
421 inline const Eigen::Vector3d &
measuredCoMd() noexcept {
return measuredCoMd_; }
425 inline const Eigen::Vector3d &
comOffsetTarget() noexcept {
return comOffsetTarget_; }
427 inline const Eigen::Vector3d &
comOffsetMeasured() const noexcept {
return comOffsetMeasured_; }
431 inline bool inContact(ContactState state)
const noexcept {
return contacts_.count(state); }
453 inline void torsoPitch(
double pitch) noexcept { c_.torsoPitch = pitch; }
455 inline double omega()
const {
return omega_; }
459 c_.torsoWeight = weight;
460 torsoTask->weight(c_.torsoWeight);
465 c_.torsoStiffness = stiffness;
466 torsoTask->stiffness(stiffness);
471 c_.pelvisWeight = weight;
472 pelvisTask->weight(c_.pelvisWeight);
477 c_.pelvisStiffness = stiffness;
478 pelvisTask->stiffness(stiffness);
481 inline void dcmGains(
double p,
double i,
double d) noexcept
483 dcmGains(Eigen::Vector2d::Constant(p), Eigen::Vector2d::Constant(i), Eigen::Vector2d::Constant(d));
486 inline void dcmGains(
const Eigen::Vector2d & p,
const Eigen::Vector2d & i,
const Eigen::Vector2d & d) noexcept
488 c_.dcmPropGain =
clamp(p, 0., c_.safetyThresholds.MAX_DCM_P_GAIN);
489 c_.dcmIntegralGain =
clamp(i, 0., c_.safetyThresholds.MAX_DCM_I_GAIN);
490 c_.dcmDerivGain =
clamp(d, 0., c_.safetyThresholds.MAX_DCM_D_GAIN);
495 c_.dcmIntegratorTimeConstant = dcmIntegratorTimeConstant;
496 dcmIntegrator_.timeConstant(dcmIntegratorTimeConstant);
503 c_.dcmDerivatorTimeConstant = T;
504 dcmDerivator_.cutoffPeriod(T);
509 c_.extWrench.extWrenchSumLowPassCutoffPeriod = cutoffPeriod;
510 extWrenchSumLowPass_.cutoffPeriod(cutoffPeriod);
515 c_.extWrench.comOffsetLowPassCutoffPeriod = cutoffPeriod;
516 comOffsetLowPass_.cutoffPeriod(cutoffPeriod);
521 c_.extWrench.comOffsetLowPassCoMCutoffPeriod = cutoffPeriod;
522 comOffsetLowPassCoM_.cutoffPeriod(cutoffPeriod);
527 c_.extWrench.comOffsetDerivatorTimeConstant = timeConstant;
528 comOffsetDerivator_.timeConstant(timeConstant);
533 c_.comWeight = weight;
534 comTask->weight(weight);
539 c_.comStiffness = stiffness;
540 comTask->stiffness(stiffness);
545 c_.contactWeight = weight;
546 for(
auto footT : contactTasks) { footT->weight(c_.contactWeight); }
551 c_.contactStiffness = stiffness;
552 for(
auto contactT : contactTasks) { contactT->stiffness(stiffness); }
557 c_.contactDamping = damping;
558 for(
auto contactT : contactTasks) { contactT->damping(damping); }
563 c_.copAdmittance =
clamp(copAdmittance, 0., c_.safetyThresholds.MAX_COP_ADMITTANCE);
564 for(
auto contactT : contactTasks) { contactT->admittance(contactAdmittance()); }
567 inline void copMaxVel(
const sva::MotionVecd & copMaxVel) noexcept
569 c_.copMaxVel = copMaxVel;
570 for(
const auto & footTask : footTasks)
572 footTask.second->maxLinearVel(copMaxVel.linear());
573 footTask.second->maxAngularVel(copMaxVel.angular());
581 for(
auto & ft : footTasks) { ft.second->velFilterGain(gain); }
589 inline void vdcStiffness(
double stiffness) noexcept { c_.vdcStiffness =
clamp(stiffness, 0., 1e4); }
593 c_.dfAdmittance =
clamp(dfAdmittance, 0., c_.safetyThresholds.MAX_DF_ADMITTANCE);
596 inline void dfDamping(Eigen::Vector3d dfDamping) noexcept
598 c_.dfDamping =
clamp(dfDamping, 0., c_.safetyThresholds.MAX_DF_DAMPING);
614 c_.safetyThresholds = thresholds;
617 copAdmittance(c_.copAdmittance);
627 auto & bc = c_.dcmBias;
629 dcmEstimator_.setBiasDriftPerSecond(bc.biasDriftPerSecondStd);
630 dcmEstimator_.setDcmMeasureErrorStd(bc.dcmMeasureErrorStd);
631 dcmEstimator_.setZmpMeasureErrorStd(bc.zmpMeasureErrorStd);
632 dcmEstimator_.setBiasLimit(bc.biasLimit);
645 c_.extWrench = extWrenchConfig;
646 extWrenchSumLowPass_.cutoffPeriod(c_.extWrench.extWrenchSumLowPassCutoffPeriod);
647 comOffsetLowPass_.cutoffPeriod(c_.extWrench.comOffsetLowPassCutoffPeriod);
648 comOffsetLowPassCoM_.cutoffPeriod(c_.extWrench.comOffsetLowPassCoMCutoffPeriod);
649 comOffsetDerivator_.timeConstant(c_.extWrench.comOffsetDerivatorTimeConstant);
656 void dimWeight(
const Eigen::VectorXd & dimW)
override;
657 Eigen::VectorXd dimWeight()
const override;
660 const std::vector<std::string> & activeJointsName,
661 const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {})
override;
664 const std::vector<std::string> & unactiveJointsName,
665 const std::map<std::string, std::vector<std::array<int, 2>>> & unactiveDofs = {})
override;
677 void checkInTheAir();
682 void computeLeftFootRatio();
692 void updateState(
const Eigen::Vector3d & com,
const Eigen::Vector3d & comd,
const Eigen::Vector3d & comdd);
702 sva::ForceVecd computeDesiredWrench();
708 void distributeWrench(
const sva::ForceVecd & desiredWrench);
723 void distributeCoPonHorizon(
const std::vector<Eigen::Vector2d> & zmp_ref,
double delta);
725 void computeCoPonHorizon(
const std::vector<Eigen::Vector2d> & zmp_ref,
const double delta,
const double t_delay);
735 void saturateWrench(
const sva::ForceVecd & desiredWrench,
736 std::shared_ptr<mc_tasks::force::CoPTask> & footTask,
740 void setSupportFootGains();
752 void updateCoMTaskZMPCC();
760 void updateFootForceDifferenceControl();
763 void updateZMPFrame();
766 inline sva::ForceVecd contactAdmittance() const noexcept
768 return {{c_.copAdmittance.y(), c_.copAdmittance.x(), 0.}, {0., 0., 0.}};
773 c_.zmpcc = zmpccConfig;
774 zmpcc_.configure(zmpccConfig);
785 template<sva::ForceVecd ExternalWrench::*TargetOrMeasured>
787 Eigen::Vector3d & offset_gamma,
788 double & coef_kappa)
const;
796 template<sva::ForceVecd ExternalWrench::*TargetOrMeasured>
797 sva::ForceVecd computeExternalWrenchSum(
const mc_rbdyn::Robot & robot,
const Eigen::Vector3d & com)
const;
809 const std::string & surfaceName,
810 const sva::ForceVecd & surfaceWrench,
811 Eigen::Vector3d & pos,
812 Eigen::Vector3d & force,
813 Eigen::Vector3d & moment)
const;
855 return static_cast<std::size_t
>(t);
858 std::unordered_map<ContactState,
861 std::equal_to<ContactState>,
862 Eigen::aligned_allocator<std::pair<const ContactState, internal::Contact>>>
870 Eigen::Vector2d supportMin_ = Eigen::Vector2d::Zero();
871 Eigen::Vector2d supportMax_ = Eigen::Vector2d::Zero();
880 Eigen::Vector3d comTargetRaw_ = Eigen::Vector3d::Zero();
881 Eigen::Vector3d comTarget_ = Eigen::Vector3d::Zero();
882 Eigen::Vector3d comdTarget_ = Eigen::Vector3d::Zero();
883 Eigen::Vector3d comddTarget_ = Eigen::Vector3d::Zero();
884 Eigen::Vector3d zmpTarget_ = Eigen::Vector3d::Zero();
885 Eigen::Vector3d zmpdTarget_ = Eigen::Vector3d::Zero();
886 Eigen::Vector3d dcmTarget_ = Eigen::Vector3d::Zero();
903 bool reconfigure_ =
true;
904 bool enabled_ =
true;
907 Eigen::Vector3d dcmAverageError_ = Eigen::Vector3d::Zero();
908 Eigen::Vector3d dcmError_ = Eigen::Vector3d::Zero();
909 Eigen::Vector3d dcmVelError_ = Eigen::Vector3d::Zero();
910 Eigen::Vector3d measuredCoM_ = Eigen::Vector3d::Zero();
911 Eigen::Vector3d measuredCoMd_ = Eigen::Vector3d::Zero();
912 Eigen::Vector3d measuredCoMdd_ = Eigen::Vector3d::Zero();
913 Eigen::Vector3d measuredZMP_ = Eigen::Vector3d::Zero();
914 Eigen::Vector3d measuredDCM_ = Eigen::Vector3d::Zero();
915 Eigen::Vector3d measuredDCMUnbiased_ = Eigen::Vector3d::Zero();
916 Eigen::Vector3d measuredCoMUnbiased_ = Eigen::Vector3d::Zero();
917 sva::ForceVecd measuredNetWrench_ = sva::ForceVecd::Zero();
919 bool zmpccOnlyDS_ =
true;
929 bool dcmEstimatorNeedsReset_ =
true;
937 sva::ForceVecd extWrenchSumTarget_ = sva::ForceVecd::Zero();
938 sva::ForceVecd extWrenchSumMeasured_ = sva::ForceVecd::Zero();
939 Eigen::Vector3d comOffsetTarget_ = Eigen::Vector3d::Zero();
940 Eigen::Vector3d comOffsetMeasured_ = Eigen::Vector3d::Zero();
941 double zmpCoefTarget_ = 1;
942 double zmpCoefMeasured_ = 1;
943 Eigen::Vector3d comOffsetErr_ = Eigen::Vector3d::Zero();
944 Eigen::Vector3d comOffsetErrCoM_ = Eigen::Vector3d::Zero();
945 Eigen::Vector3d comOffsetErrZMP_ = Eigen::Vector3d::Zero();
956 bool inTheAir_ =
false;
957 bool wasInTheAir_ =
false;
958 bool wasEnabled_ =
true;
959 Eigen::Vector3d dfForceError_ = Eigen::Vector3d::Zero();
960 Eigen::Vector3d dfError_ = Eigen::Vector3d::Zero();
962 double leftFootRatio_ = 0.5;
964 double runTime_ = 0.;
965 double vdcHeightError_ = 0;
966 sva::ForceVecd desiredWrench_ = sva::ForceVecd::Zero();
967 sva::ForceVecd distribWrench_ = sva::ForceVecd::Zero();
968 Eigen::Vector3d distribZMP_ =
969 Eigen::Vector3d::Zero();
970 sva::PTransformd zmpFrame_ = sva::PTransformd::Identity();
975 double horizonDelta_ = 0.05;
977 bool horizonCoPDistribution_ =
false;
978 bool horizonRefUpdated_ =
false;
979 Eigen::Vector2d modeledCoPLeft_ = Eigen::Vector2d::Zero();
980 Eigen::Vector2d modeledCoPRight_ = Eigen::Vector2d::Zero();
982 Eigen::Vector2d delayedTargetCoPLeft_ = Eigen::Vector2d::Zero();
983 Eigen::Vector2d delayedTargetCoPRight_ = Eigen::Vector2d::Zero();
984 double delayedTargetFzLeft_ = 0;
985 double delayedTargetFzRight_ = 0;
987 double tComputation_ = 0.;
988 double modeledFzRight_ = 0.;
989 double modeledFzLeft_ = 0.;
990 double desiredFzLeft_ = 0.;
991 double desiredFzRight_ = 0.;
992 Eigen::Vector2d QPCoPLeft_ =
993 Eigen::Vector2d::Zero();
994 Eigen::Vector2d QPCoPRight_ =
995 Eigen::Vector2d::Zero();
997 Eigen::Vector2d distribCheck_ = Eigen::Vector2d::Zero();
1004 extern template void StabilizerTask::computeWrenchOffsetAndCoefficient<&StabilizerTask::ExternalWrench::target>(
1006 Eigen::Vector3d & offset_gamma,
1007 double & coef_kappa)
const;
1008 extern template void StabilizerTask::computeWrenchOffsetAndCoefficient<&StabilizerTask::ExternalWrench::measured>(
1010 Eigen::Vector3d & offset_gamma,
1011 double & coef_kappa)
const;
1013 extern template sva::ForceVecd StabilizerTask::computeExternalWrenchSum<&StabilizerTask::ExternalWrench::target>(
1015 const Eigen::Vector3d &)
const;
1016 extern template sva::ForceVecd StabilizerTask::computeExternalWrenchSum<&StabilizerTask::ExternalWrench::measured>(
1018 const Eigen::Vector3d &)
const;
void dcmIntegratorTimeConstant(double dcmIntegratorTimeConstant) noexcept
Definition: StabilizerTask.h:493
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
const Eigen::Vector3d & targetCoM() const noexcept
Returns the CoM target used for stabilization.
Definition: StabilizerTask.h:339
mc_rbdyn::lipm_stabilizer::ExternalWrenchConfiguration ExternalWrenchConfiguration
Definition: StabilizerTask.h:41
void vdcFrequency(double freq) noexcept
Definition: StabilizerTask.h:587
std::vector< ContactDescription, Eigen::aligned_allocator< ContactDescription > > ContactDescriptionVector
Definition: Contact.h:199
Eigen::Vector3d MC_RBDYN_DLLAPI zmp(const sva::ForceVecd &netTotalWrench, const Eigen::Vector3d &plane_p, const Eigen::Vector3d &plane_n, double minimalNetNormalForce=1.)
Actual ZMP computation from net total wrench and the ZMP plane.
void comOffsetLowPassCoMCutoffPeriod(double cutoffPeriod) noexcept
Definition: StabilizerTask.h:519
std::unordered_map< ContactState, internal::Contact, EnumClassHash, std::equal_to< ContactState >, Eigen::aligned_allocator< std::pair< const ContactState, internal::Contact > > > contacts_
Definition: StabilizerTask.h:863
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)
Definition: StabilizerTask.h:368
ZMPCC zmpcc_
Definition: StabilizerTask.h:920
const Eigen::Vector3d & measuredCoM() noexcept
Definition: StabilizerTask.h:419
void copMaxVel(const sva::MotionVecd &copMaxVel) noexcept
Definition: StabilizerTask.h:567
mc_filter::LowPass< Eigen::Vector3d > comOffsetLowPass_
Definition: StabilizerTask.h:948
void externalWrenchConfiguration(const ExternalWrenchConfiguration &extWrenchConfig) noexcept
Changes the parameters for the external wrenches.
Definition: StabilizerTask.h:643
const DCMBiasEstimatorConfiguration & dcmBiasEstimatorConfiguration() const noexcept
Get parameters of the DCM bias estimator.
Definition: StabilizerTask.h:636
const Eigen::Vector3d & measuredCoMd() noexcept
Definition: StabilizerTask.h:421
mc_filter::StationaryOffset< Eigen::Vector3d > comOffsetDerivator_
Definition: StabilizerTask.h:951
void copVelFilterGain(double gain) noexcept
Definition: StabilizerTask.h:578
void copAdmittance(const Eigen::Vector2d &copAdmittance) noexcept
Definition: StabilizerTask.h:561
void dcmGains(double p, double i, double d) noexcept
Definition: StabilizerTask.h:481
void dcmBiasEstimatorConfiguration(const DCMBiasEstimatorConfiguration &biasConfig) noexcept
Changes the parameters of the DCM bias estimator.
Definition: StabilizerTask.h:625
#define MC_TASKS_DLLAPI
Definition: api.h:50
void contactWeight(double weight) noexcept
Definition: StabilizerTask.h:543
mc_filter::ExponentialMovingAverage< Eigen::Vector3d > dcmIntegrator_
Definition: StabilizerTask.h:954
void comWeight(double weight) noexcept
Definition: StabilizerTask.h:531
Workaround a C++11 standard bug: no specialization of the hash functor exists for enum types....
Definition: StabilizerTask.h:850
void contactStiffness(const sva::MotionVecd &stiffness) noexcept
Definition: StabilizerTask.h:549
Definition: QPSolver.h:85
EIGEN_MAKE_ALIGNED_OPERATOR_NEW sva::ForceVecd target
Target (expected) external wrench.
Definition: StabilizerTask.h:65
std::shared_ptr< mc_tasks::CoMTask > comTask
Definition: StabilizerTask.h:872
mc_rbdyn::lipm_stabilizer::FDQPWeights FDQPWeights
Definition: StabilizerTask.h:38
ContactState supportFoot() const noexcept
Definition: StabilizerTask.h:354
StabilizerConfiguration lastConfig_
Definition: StabilizerTask.h:896
void fdqpWeights(const FDQPWeights &fdqp) noexcept
Definition: StabilizerTask.h:601
mc_filter::LowPass< sva::ForceVecd > extWrenchSumLowPass_
Definition: StabilizerTask.h:947
void name(const std::string &name) override
Definition: StabilizerTask.h:113
Definition: ZMPCCConfiguration.h:14
void safetyThresholds(const SafetyThresholds &thresholds) noexcept
Changes the safety thresholds.
Definition: StabilizerTask.h:612
Eigen::Vector2d filteredDCM() const noexcept
Definition: StabilizerTask.h:411
void torsoWeight(double weight) noexcept
Definition: StabilizerTask.h:457
sva::MotionVecd gain
Gain of measured external wrench.
Definition: StabilizerTask.h:69
void vdcStiffness(double stiffness) noexcept
Definition: StabilizerTask.h:589
const Eigen::Vector3d & measuredZMP() noexcept
Definition: StabilizerTask.h:417
Definition: StabilizerConfiguration.h:167
std::vector< ContactState > addContacts_
Definition: StabilizerTask.h:864
std::string surfaceName
Name of the surface to which the external wrench is applied.
Definition: StabilizerTask.h:71
const Eigen::Vector3d & comOffsetTarget() noexcept
Definition: StabilizerTask.h:425
double omega() const
Definition: StabilizerTask.h:455
std::vector< Eigen::Vector2d > horizonZmpRef_
Definition: StabilizerTask.h:974
StabilizerConfiguration c_
Definition: StabilizerTask.h:900
const Eigen::Vector2d biasDCM() noexcept
Definition: StabilizerTask.h:405
mc_rbdyn::lipm_stabilizer::ZMPCCConfiguration ZMPCCConfiguration
Definition: StabilizerTask.h:36
void comStiffness(const Eigen::Vector3d &stiffness) noexcept
Definition: StabilizerTask.h:537
const Eigen::Vector3d & targetCoMRaw() const noexcept
Return the raw CoM target as provided by target().
Definition: StabilizerTask.h:330
const Eigen::Vector3d & measuredDCM() noexcept
Definition: StabilizerTask.h:403
std::vector< ExternalWrench > extWrenches_
Definition: StabilizerTask.h:936
Logs controller data to disk.
Definition: Logger.h:29
std::vector< std::shared_ptr< mc_tasks::force::CoPTask > > contactTasks
Definition: StabilizerTask.h:866
std::unordered_map< ContactState, std::shared_ptr< mc_tasks::force::CoPTask >, EnumClassHash > footTasks
Definition: StabilizerTask.h:865
mc_filter::LowPassCompose< Eigen::Vector3d > dcmDerivator_
Definition: StabilizerTask.h:955
mc_rbdyn::lipm_stabilizer::SafetyThresholds SafetyThresholds
Definition: StabilizerTask.h:39
StabilizerConfiguration disableConfig_
Definition: StabilizerTask.h:898
const std::string & footSurface(ContactState s) const
Definition: StabilizerTask.h:263
const ExternalWrenchConfiguration & externalWrenchConfiguration() const noexcept
Get the parameters for the external wrenches.
Definition: StabilizerTask.h:653
sva::ForceVecd measured
Measured external wrench.
Definition: StabilizerTask.h:67
const mc_rbdyn::Robot & realRobot() const noexcept
Definition: StabilizerTask.h:437
Definition: StabilizerTask.h:56
unsigned int robotIndex_
Definition: StabilizerTask.h:877
std::size_t operator()(T t) const
Definition: StabilizerTask.h:853
void comOffsetDerivatorTimeConstant(double timeConstant) noexcept
Definition: StabilizerTask.h:525
Definition: StateBuilder.h:27
double leftFootRatio() const noexcept
Interpolation paremeter between left and right foot.
Definition: StabilizerTask.h:270
bool inContact(ContactState state) const noexcept
Definition: StabilizerTask.h:431
const std::vector< ExternalWrench > & externalWrenches() const noexcept
Definition: StabilizerTask.h:396
const sva::PTransformd & contactAnklePose(ContactState s) const
Projected pose of the ankle frame in the contact frame.
Definition: StabilizerTask.h:261
External wrench.
Definition: StabilizerTask.h:61
stateObservation::LipmDcmEstimator dcmEstimator_
Definition: StabilizerTask.h:927
Stabilizer safety thresholds.
Definition: StabilizerConfiguration.h:98
const mc_rbdyn::Robot & robot() const noexcept
Definition: StabilizerTask.h:435
double clamp(double value, double lower, double upper)
Definition: clamp.h:29
std::shared_ptr< mc_tasks::OrientationTask > torsoTask
Definition: StabilizerTask.h:874
const mc_rbdyn::Robots & robots_
Definition: StabilizerTask.h:875
void extWrenchSumLowPassCutoffPeriod(double cutoffPeriod) noexcept
Definition: StabilizerTask.h:507
void supportFoot(const ContactState &foot) noexcept
Definition: StabilizerTask.h:357
Parameters for the external wrenches.
Definition: StabilizerConfiguration.h:260
mc_filter::LowPass< Eigen::Vector3d > fSumFilter_
Definition: StabilizerTask.h:998
double zmpCoeffMeasured() const noexcept
Definition: StabilizerTask.h:429
void torsoPitch(double pitch) noexcept
Definition: StabilizerTask.h:453
Eigen::QuadProgDense qpSolver_
Definition: StabilizerTask.h:906
mc_filter::LowPass< Eigen::Vector3d > comOffsetLowPassCoM_
Definition: StabilizerTask.h:950
void comOffsetLowPassCutoffPeriod(double cutoffPeriod) noexcept
Definition: StabilizerTask.h:513
const mc_rbdyn::Robots & realRobots_
Definition: StabilizerTask.h:876
Definition: StabilizerConfiguration.h:22
const Eigen::Vector3d & measuredFilteredNetForces() const noexcept
Definition: StabilizerTask.h:423
std::vector< std::vector< Eigen::Vector3d > > supportPolygons_
Definition: StabilizerTask.h:869
const Eigen::Vector3d & targetZMPVelocity() const noexcept
Definition: StabilizerTask.h:351
void torsoStiffness(double stiffness) noexcept
Definition: StabilizerTask.h:463
void dfDamping(Eigen::Vector3d dfDamping) noexcept
Definition: StabilizerTask.h:596
mc_control::Contact Contact
Definition: Controller.h:22
std::vector< std::string > contactSensors
Definition: StabilizerTask.h:867
double copVelFilterGain() const noexcept
Definition: StabilizerTask.h:585
void pelvisWeight(double weight) noexcept
Definition: StabilizerTask.h:469
Configuration of the LIPMStabilizer. This configuration is meant to be overriden from the RobotModule...
Definition: StabilizerConfiguration.h:434
MC_RTC_DEPRECATED void dcmDerivatorTimeConstant(double T) noexcept
Definition: StabilizerTask.h:499
const Eigen::Vector3d & targetCoMAcceleration() const noexcept
Definition: StabilizerTask.h:345
const Eigen::Vector3d & comOffsetMeasured() const noexcept
Definition: StabilizerTask.h:427
std::shared_ptr< mc_tasks::OrientationTask > pelvisTask
Definition: StabilizerTask.h:873
const Eigen::Vector3d & targetCoMVelocity() const noexcept
Definition: StabilizerTask.h:342
mc_rbdyn::lipm_stabilizer::DCMBiasEstimatorConfiguration DCMBiasEstimatorConfiguration
Definition: StabilizerTask.h:40
const Eigen::Vector3d & distribZMP() const noexcept
Definition: StabilizerTask.h:401
const Eigen::Vector3d & targetZMP() const noexcept
Definition: StabilizerTask.h:348
bool inDoubleSupport() const noexcept
Definition: StabilizerTask.h:433
void dcmDerivatorCutoffPeriod(double T) noexcept
Definition: StabilizerTask.h:501
void pelvisStiffness(double stiffness) noexcept
Definition: StabilizerTask.h:475
Definition: StabilizerStandingState.h:11
Left
Definition: types.h:158
mc_rbdyn::lipm_stabilizer::StabilizerConfiguration StabilizerConfiguration
Definition: StabilizerTask.h:37
void dcmGains(const Eigen::Vector2d &p, const Eigen::Vector2d &i, const Eigen::Vector2d &d) noexcept
Definition: StabilizerTask.h:486
StabilizerConfiguration defaultConfig_
Definition: StabilizerTask.h:894
void contactDamping(const sva::MotionVecd &damping) noexcept
Definition: StabilizerTask.h:555
void dfAdmittance(Eigen::Vector3d dfAdmittance) noexcept
Definition: StabilizerTask.h:591