StabilizerTask.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2019 CNRS-UM LIRMM, CNRS-AIST JRL
3  *
4  * This file is inspired by Stephane's Caron original implementation as part of
5  * lipm_walking_controller <https://github.com/stephane-caron/lipm_walking_controller>
6  */
7 
8 #pragma once
9 
12 #include <mc_filter/LowPass.h>
16 #include <mc_rtc/deprecated.h>
17 #include <mc_tasks/CoMTask.h>
18 #include <mc_tasks/CoPTask.h>
19 #include <mc_tasks/MetaTask.h>
23 
24 #include <state-observation/dynamics-estimators/lipm-dcm-estimator.hpp>
25 
26 #include <Eigen/QR>
27 #include <eigen-quadprog/QuadProg.h>
28 
29 namespace mc_tasks
30 {
31 
32 namespace lipm_stabilizer
33 {
34 
42 
57 {
58  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59 
62  {
63  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
65  sva::ForceVecd target;
67  sva::ForceVecd measured;
69  sva::MotionVecd gain;
71  std::string surfaceName;
72  };
73 
86  StabilizerTask(const mc_rbdyn::Robots & robots,
87  const mc_rbdyn::Robots & realRobots,
88  unsigned int robotIndex,
89  const std::string & leftSurface,
90  const std::string & rightSurface,
91  const std::string & torsoBodyName,
92  double dt);
93 
108  StabilizerTask(const mc_rbdyn::Robots & robots,
109  const mc_rbdyn::Robots & realRobots,
110  unsigned int robotIndex,
111  double dt);
112 
113  inline void name(const std::string & name) override
114  {
115  name_ = name;
116 
117  // Rename the tasks managed by the stabilizer
118  // Doing so helps making the logs more consistent, and having a fixed name
119  // allows for predifined custom plots in the log ui.
120  const auto n = name_ + "_Tasks";
121  comTask->name(n + "_com");
122  footTasks.at(ContactState::Left)->name(n + "_cop_left");
123  footTasks.at(ContactState::Right)->name(n + "_cop_right");
124  pelvisTask->name(n + "_pelvis");
125  torsoTask->name(n + "_torso");
126  }
127 
128  using MetaTask::name;
129 
145  void reset() override;
146 
153  Eigen::VectorXd eval() const override;
154 
161  Eigen::VectorXd speed() const override;
162 
169  void enable();
170 
172  void disable();
173 
182  void configure(const StabilizerConfiguration & config);
183 
187  void commitConfig();
188 
190  void load(mc_solver::QPSolver &, const mc_rtc::Configuration & config) override;
191 
198  const StabilizerConfiguration & config() const;
199 
208  const StabilizerConfiguration & commitedConfig() const;
209 
215  void reconfigure();
216 
221  void run();
222 
235  void setContacts(const ContactDescriptionVector & contacts);
236 
243  void setContacts(const std::vector<std::pair<ContactState, sva::PTransformd>> & contacts);
244 
252  void setContacts(const std::vector<ContactState> & contacts);
253 
261  inline const sva::PTransformd & contactAnklePose(ContactState s) const { return contacts_.at(s).anklePose(); }
262 
263  inline const std::string & footSurface(ContactState s) const { return footTasks.at(s)->surface(); }
264 
270  inline double leftFootRatio() const noexcept { return leftFootRatio_; }
271 
280  sva::PTransformd anchorFrame(const mc_rbdyn::Robot & robot) const;
281 
295  void staticTarget(const Eigen::Vector3d & com, double zmpHeight = 0);
296 
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());
322 
330  inline const Eigen::Vector3d & targetCoMRaw() const noexcept { return comTargetRaw_; }
331 
339  inline const Eigen::Vector3d & targetCoM() const noexcept { return comTargetRaw_; }
340 
341  /* Return the target CoM velocity provided by \ref stabilizer_target "target()" */
342  inline const Eigen::Vector3d & targetCoMVelocity() const noexcept { return comdTarget_; }
343 
344  /* Return the target CoM acceleration provided by \ref stabilizer_target "target()" */
345  inline const Eigen::Vector3d & targetCoMAcceleration() const noexcept { return comddTarget_; }
346 
347  /* Return the target ZMP provided by \ref stabilizer_target "target()" */
348  inline const Eigen::Vector3d & targetZMP() const noexcept { return zmpTarget_; }
349 
350  /* Return the target ZMP velocity by \ref stabilizer_target "target()" */
351  inline const Eigen::Vector3d & targetZMPVelocity() const noexcept { return zmpdTarget_; }
352 
353  /* Return the current support foot */
354  inline ContactState supportFoot() const noexcept { return supportFoot_; }
355 
356  /* Set the current support foot */
357  inline void supportFoot(const ContactState & foot) noexcept { supportFoot_ = foot; }
358 
368  inline void horizonReference(const std::vector<Eigen::Vector2d> & ref, const double delta) noexcept
369  {
370  horizonZmpRef_ = ref;
371  horizonDelta_ = delta;
372  horizonCoPDistribution_ = true;
373  horizonRefUpdated_ = true;
374  }
375 
388  void setExternalWrenches(const std::vector<std::string> & surfaceNames,
389  const std::vector<sva::ForceVecd> & targetWrenches,
390  const std::vector<sva::MotionVecd> & gains);
391 
392  /* Return the current external wrenches targets
393  *
394  * \see \ref set_external_wrenches "setExternalWrenches()"
395  **/
396  inline const std::vector<ExternalWrench> & externalWrenches() const noexcept { return extWrenches_; }
397 
398  /*
399  * Return the ZMP from the wrenches distribution
400  **/
401  inline const Eigen::Vector3d & distribZMP() const noexcept { return distribZMP_; }
402 
403  inline const Eigen::Vector3d & measuredDCM() noexcept { return measuredDCM_; }
404 
405  inline const Eigen::Vector2d biasDCM() noexcept
406  {
407  if(c_.dcmBias.withDCMBias) { return dcmEstimator_.getBias(); }
408  return Eigen::Vector2d::Zero();
409  }
410 
411  inline Eigen::Vector2d filteredDCM() const noexcept
412  {
413  if(c_.dcmBias.withDCMBias) { return dcmEstimator_.getUnbiasedDCM(); }
414  return measuredDCM_.segment(0, 2);
415  }
416 
417  inline const Eigen::Vector3d & measuredZMP() noexcept { return measuredZMP_; }
418 
419  inline const Eigen::Vector3d & measuredCoM() noexcept { return measuredCoM_; }
420 
421  inline const Eigen::Vector3d & measuredCoMd() noexcept { return measuredCoMd_; }
422 
423  inline const Eigen::Vector3d & measuredFilteredNetForces() const noexcept { return fSumFilter_.eval(); }
424 
425  inline const Eigen::Vector3d & comOffsetTarget() noexcept { return comOffsetTarget_; }
426 
427  inline const Eigen::Vector3d & comOffsetMeasured() const noexcept { return comOffsetMeasured_; }
428 
429  inline double zmpCoeffMeasured() const noexcept { return zmpCoefMeasured_; }
430 
431  inline bool inContact(ContactState state) const noexcept { return contacts_.count(state); }
432 
433  inline bool inDoubleSupport() const noexcept { return contacts_.size() == 2; }
434 
435  inline const mc_rbdyn::Robot & robot() const noexcept { return robots_.robot(robotIndex_); }
436 
437  inline const mc_rbdyn::Robot & realRobot() const noexcept { return realRobots_.robot(robotIndex_); }
438 
453  inline void torsoPitch(double pitch) noexcept { c_.torsoPitch = pitch; }
454 
455  inline double omega() const { return omega_; }
456 
457  inline void torsoWeight(double weight) noexcept
458  {
459  c_.torsoWeight = weight;
460  torsoTask->weight(c_.torsoWeight);
461  }
462 
463  inline void torsoStiffness(double stiffness) noexcept
464  {
465  c_.torsoStiffness = stiffness;
466  torsoTask->stiffness(stiffness);
467  }
468 
469  inline void pelvisWeight(double weight) noexcept
470  {
471  c_.pelvisWeight = weight;
472  pelvisTask->weight(c_.pelvisWeight);
473  }
474 
475  inline void pelvisStiffness(double stiffness) noexcept
476  {
477  c_.pelvisStiffness = stiffness;
478  pelvisTask->stiffness(stiffness);
479  }
480 
481  inline void dcmGains(double p, double i, double d) noexcept
482  {
483  dcmGains(Eigen::Vector2d::Constant(p), Eigen::Vector2d::Constant(i), Eigen::Vector2d::Constant(d));
484  }
485 
486  inline void dcmGains(const Eigen::Vector2d & p, const Eigen::Vector2d & i, const Eigen::Vector2d & d) noexcept
487  {
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);
491  }
492 
493  inline void dcmIntegratorTimeConstant(double dcmIntegratorTimeConstant) noexcept
494  {
495  c_.dcmIntegratorTimeConstant = dcmIntegratorTimeConstant;
496  dcmIntegrator_.timeConstant(dcmIntegratorTimeConstant);
497  }
498 
499  MC_RTC_DEPRECATED inline void dcmDerivatorTimeConstant(double T) noexcept { dcmDerivatorCutoffPeriod(T); }
500 
501  inline void dcmDerivatorCutoffPeriod(double T) noexcept
502  {
503  c_.dcmDerivatorTimeConstant = T;
504  dcmDerivator_.cutoffPeriod(T);
505  }
506 
507  inline void extWrenchSumLowPassCutoffPeriod(double cutoffPeriod) noexcept
508  {
509  c_.extWrench.extWrenchSumLowPassCutoffPeriod = cutoffPeriod;
510  extWrenchSumLowPass_.cutoffPeriod(cutoffPeriod);
511  }
512 
513  inline void comOffsetLowPassCutoffPeriod(double cutoffPeriod) noexcept
514  {
515  c_.extWrench.comOffsetLowPassCutoffPeriod = cutoffPeriod;
516  comOffsetLowPass_.cutoffPeriod(cutoffPeriod);
517  }
518 
519  inline void comOffsetLowPassCoMCutoffPeriod(double cutoffPeriod) noexcept
520  {
521  c_.extWrench.comOffsetLowPassCoMCutoffPeriod = cutoffPeriod;
522  comOffsetLowPassCoM_.cutoffPeriod(cutoffPeriod);
523  }
524 
525  inline void comOffsetDerivatorTimeConstant(double timeConstant) noexcept
526  {
527  c_.extWrench.comOffsetDerivatorTimeConstant = timeConstant;
528  comOffsetDerivator_.timeConstant(timeConstant);
529  }
530 
531  inline void comWeight(double weight) noexcept
532  {
533  c_.comWeight = weight;
534  comTask->weight(weight);
535  }
536 
537  inline void comStiffness(const Eigen::Vector3d & stiffness) noexcept
538  {
539  c_.comStiffness = stiffness;
540  comTask->stiffness(stiffness);
541  }
542 
543  inline void contactWeight(double weight) noexcept
544  {
545  c_.contactWeight = weight;
546  for(auto footT : contactTasks) { footT->weight(c_.contactWeight); }
547  }
548 
549  inline void contactStiffness(const sva::MotionVecd & stiffness) noexcept
550  {
551  c_.contactStiffness = stiffness;
552  for(auto contactT : contactTasks) { contactT->stiffness(stiffness); }
553  }
554 
555  inline void contactDamping(const sva::MotionVecd & damping) noexcept
556  {
557  c_.contactDamping = damping;
558  for(auto contactT : contactTasks) { contactT->damping(damping); }
559  }
560 
561  inline void copAdmittance(const Eigen::Vector2d & copAdmittance) noexcept
562  {
563  c_.copAdmittance = clamp(copAdmittance, 0., c_.safetyThresholds.MAX_COP_ADMITTANCE);
564  for(auto contactT : contactTasks) { contactT->admittance(contactAdmittance()); }
565  }
566 
567  inline void copMaxVel(const sva::MotionVecd & copMaxVel) noexcept
568  {
569  c_.copMaxVel = copMaxVel;
570  for(const auto & footTask : footTasks)
571  {
572  footTask.second->maxLinearVel(copMaxVel.linear());
573  footTask.second->maxAngularVel(copMaxVel.angular());
574  }
575  }
576 
577  /* Set the gain of the low-pass velocity filter of the cop tasks */
578  inline void copVelFilterGain(double gain) noexcept
579  {
580  c_.copVelFilterGain = mc_filter::utils::clamp(gain, 0, 1);
581  for(auto & ft : footTasks) { ft.second->velFilterGain(gain); }
582  }
583 
584  /* Get the gain of the low-pass velocity filter of the cop tasks */
585  inline double copVelFilterGain() const noexcept { return c_.copVelFilterGain; }
586 
587  inline void vdcFrequency(double freq) noexcept { c_.vdcFrequency = clamp(freq, 0., 10.); }
588 
589  inline void vdcStiffness(double stiffness) noexcept { c_.vdcStiffness = clamp(stiffness, 0., 1e4); }
590 
591  inline void dfAdmittance(Eigen::Vector3d dfAdmittance) noexcept
592  {
593  c_.dfAdmittance = clamp(dfAdmittance, 0., c_.safetyThresholds.MAX_DF_ADMITTANCE);
594  }
595 
596  inline void dfDamping(Eigen::Vector3d dfDamping) noexcept
597  {
598  c_.dfDamping = clamp(dfDamping, 0., c_.safetyThresholds.MAX_DF_DAMPING);
599  }
600 
601  inline void fdqpWeights(const FDQPWeights & fdqp) noexcept { c_.fdqpWeights = fdqp; }
602 
612  inline void safetyThresholds(const SafetyThresholds & thresholds) noexcept
613  {
614  c_.safetyThresholds = thresholds;
615  c_.clampGains();
616  // only requried because we want to apply the new gains immediately
617  copAdmittance(c_.copAdmittance);
618  }
619 
625  inline void dcmBiasEstimatorConfiguration(const DCMBiasEstimatorConfiguration & biasConfig) noexcept
626  {
627  auto & bc = c_.dcmBias;
628  bc = biasConfig;
629  dcmEstimator_.setBiasDriftPerSecond(bc.biasDriftPerSecondStd);
630  dcmEstimator_.setDcmMeasureErrorStd(bc.dcmMeasureErrorStd);
631  dcmEstimator_.setZmpMeasureErrorStd(bc.zmpMeasureErrorStd);
632  dcmEstimator_.setBiasLimit(bc.biasLimit);
633  }
634 
636  inline const DCMBiasEstimatorConfiguration & dcmBiasEstimatorConfiguration() const noexcept { return c_.dcmBias; }
637 
643  inline void externalWrenchConfiguration(const ExternalWrenchConfiguration & extWrenchConfig) noexcept
644  {
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);
650  }
651 
653  inline const ExternalWrenchConfiguration & externalWrenchConfiguration() const noexcept { return c_.extWrench; }
654 
655 private:
656  void dimWeight(const Eigen::VectorXd & dimW) override;
657  Eigen::VectorXd dimWeight() const override;
658 
659  void selectActiveJoints(mc_solver::QPSolver & solver,
660  const std::vector<std::string> & activeJointsName,
661  const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {}) override;
662 
663  void selectUnactiveJoints(mc_solver::QPSolver & solver,
664  const std::vector<std::string> & unactiveJointsName,
665  const std::map<std::string, std::vector<std::array<int, 2>>> & unactiveDofs = {}) override;
666 
667  void resetJointsSelector(mc_solver::QPSolver & solver) override;
668 
674  void addContact(ContactState contactState, const internal::Contact & contact);
675 
677  void checkInTheAir();
678 
682  void computeLeftFootRatio();
683 
692  void updateState(const Eigen::Vector3d & com, const Eigen::Vector3d & comd, const Eigen::Vector3d & comdd);
693 
699  void updateContacts(mc_solver::QPSolver & solver);
700 
702  sva::ForceVecd computeDesiredWrench();
703 
708  void distributeWrench(const sva::ForceVecd & desiredWrench);
709 
723  void distributeCoPonHorizon(const std::vector<Eigen::Vector2d> & zmp_ref, double delta);
724 
725  void computeCoPonHorizon(const std::vector<Eigen::Vector2d> & zmp_ref, const double delta, const double t_delay);
726 
735  void saturateWrench(const sva::ForceVecd & desiredWrench,
736  std::shared_ptr<mc_tasks::force::CoPTask> & footTask,
737  const internal::Contact & contact);
738 
740  void setSupportFootGains();
741 
752  void updateCoMTaskZMPCC();
753 
760  void updateFootForceDifferenceControl();
761 
763  void updateZMPFrame();
764 
766  inline sva::ForceVecd contactAdmittance() const noexcept
767  {
768  return {{c_.copAdmittance.y(), c_.copAdmittance.x(), 0.}, {0., 0., 0.}};
769  }
770 
771  inline void zmpcc(const ZMPCCConfiguration & zmpccConfig) noexcept
772  {
773  c_.zmpcc = zmpccConfig;
774  zmpcc_.configure(zmpccConfig);
775  }
776 
785  template<sva::ForceVecd ExternalWrench::*TargetOrMeasured>
786  void computeWrenchOffsetAndCoefficient(const mc_rbdyn::Robot & robot,
787  Eigen::Vector3d & offset_gamma,
788  double & coef_kappa) const;
789 
796  template<sva::ForceVecd ExternalWrench::*TargetOrMeasured>
797  sva::ForceVecd computeExternalWrenchSum(const mc_rbdyn::Robot & robot, const Eigen::Vector3d & com) const;
798 
808  void computeExternalContact(const mc_rbdyn::Robot & robot,
809  const std::string & surfaceName,
810  const sva::ForceVecd & surfaceWrench,
811  Eigen::Vector3d & pos,
812  Eigen::Vector3d & force,
813  Eigen::Vector3d & moment) const;
814 
815  /* Task-related properties */
816 protected:
817  void addToSolver(mc_solver::QPSolver & solver) override;
818  void removeFromSolver(mc_solver::QPSolver & solver) override;
819  void removeFromGUI(mc_rtc::gui::StateBuilder &) override;
820  void update(mc_solver::QPSolver &) override;
821 
826  void addToLogger(mc_rtc::Logger &) override;
827  void removeFromLogger(mc_rtc::Logger &) override;
828  void addToGUI(mc_rtc::gui::StateBuilder &) override;
829 
836  void configure_(mc_solver::QPSolver & solver);
837  void disable_();
838 
840  void checkConfiguration(const StabilizerConfiguration & config);
841 
842 protected:
851  {
852  template<typename T>
853  std::size_t operator()(T t) const
854  {
855  return static_cast<std::size_t>(t);
856  }
857  };
858  std::unordered_map<ContactState,
860  EnumClassHash,
861  std::equal_to<ContactState>,
862  Eigen::aligned_allocator<std::pair<const ContactState, internal::Contact>>>
864  std::vector<ContactState> addContacts_;
865  std::unordered_map<ContactState, std::shared_ptr<mc_tasks::force::CoPTask>, EnumClassHash> footTasks;
866  std::vector<std::shared_ptr<mc_tasks::force::CoPTask>> contactTasks;
867  std::vector<std::string> contactSensors;
869  std::vector<std::vector<Eigen::Vector3d>> supportPolygons_;
870  Eigen::Vector2d supportMin_ = Eigen::Vector2d::Zero();
871  Eigen::Vector2d supportMax_ = Eigen::Vector2d::Zero();
872  std::shared_ptr<mc_tasks::CoMTask> comTask;
873  std::shared_ptr<mc_tasks::OrientationTask> pelvisTask;
874  std::shared_ptr<mc_tasks::OrientationTask> torsoTask;
877  unsigned int robotIndex_;
878 
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();
887  double omega_ = 3.4;
888 
889  double t_ = 0.;
891 protected:
903  bool reconfigure_ = true;
904  bool enabled_ = true;
906  Eigen::QuadProgDense qpSolver_;
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();
918 
919  bool zmpccOnlyDS_ = true;
927  stateObservation::LipmDcmEstimator dcmEstimator_;
929  bool dcmEstimatorNeedsReset_ = true;
930 
936  std::vector<ExternalWrench> extWrenches_;
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();
961  double dt_ = 0.005;
962  double leftFootRatio_ = 0.5;
963  double mass_ = 38.;
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();
972  // CoP distribution over an horizon
973  //{
974  std::vector<Eigen::Vector2d> horizonZmpRef_;
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();
999  ContactState supportFoot_ = ContactState::Left;
1001  //}
1002 };
1003 
1004 extern template void StabilizerTask::computeWrenchOffsetAndCoefficient<&StabilizerTask::ExternalWrench::target>(
1005  const mc_rbdyn::Robot & robot,
1006  Eigen::Vector3d & offset_gamma,
1007  double & coef_kappa) const;
1008 extern template void StabilizerTask::computeWrenchOffsetAndCoefficient<&StabilizerTask::ExternalWrench::measured>(
1009  const mc_rbdyn::Robot & robot,
1010  Eigen::Vector3d & offset_gamma,
1011  double & coef_kappa) const;
1012 
1013 extern template sva::ForceVecd StabilizerTask::computeExternalWrenchSum<&StabilizerTask::ExternalWrench::target>(
1014  const mc_rbdyn::Robot &,
1015  const Eigen::Vector3d &) const;
1016 extern template sva::ForceVecd StabilizerTask::computeExternalWrenchSum<&StabilizerTask::ExternalWrench::measured>(
1017  const mc_rbdyn::Robot &,
1018  const Eigen::Vector3d &) const;
1019 
1020 } // namespace lipm_stabilizer
1021 } // namespace mc_tasks
mc_tasks::lipm_stabilizer::StabilizerTask::dcmIntegratorTimeConstant
void dcmIntegratorTimeConstant(double dcmIntegratorTimeConstant) noexcept
Definition: StabilizerTask.h:493
mc_rtc::Configuration
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
mc_tasks::lipm_stabilizer::StabilizerTask::targetCoM
const Eigen::Vector3d & targetCoM() const noexcept
Returns the CoM target used for stabilization.
Definition: StabilizerTask.h:339
mc_rbdyn::Robots
Definition: Robots.h:15
mc_tasks::lipm_stabilizer::ExternalWrenchConfiguration
mc_rbdyn::lipm_stabilizer::ExternalWrenchConfiguration ExternalWrenchConfiguration
Definition: StabilizerTask.h:41
mc_tasks::lipm_stabilizer::StabilizerTask::vdcFrequency
void vdcFrequency(double freq) noexcept
Definition: StabilizerTask.h:587
LowPassCompose.h
mc_tasks::lipm_stabilizer::ContactDescriptionVector
std::vector< ContactDescription, Eigen::aligned_allocator< ContactDescription > > ContactDescriptionVector
Definition: Contact.h:199
mc_rbdyn::zmp
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.
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPassCoMCutoffPeriod
void comOffsetLowPassCoMCutoffPeriod(double cutoffPeriod) noexcept
Definition: StabilizerTask.h:519
mc_tasks::lipm_stabilizer::StabilizerTask::contacts_
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
mc_tasks::lipm_stabilizer::StabilizerTask::horizonReference
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
mc_tasks::lipm_stabilizer::StabilizerTask::zmpcc_
ZMPCC zmpcc_
Definition: StabilizerTask.h:920
mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoM
const Eigen::Vector3d & measuredCoM() noexcept
Definition: StabilizerTask.h:419
mc_tasks::lipm_stabilizer::StabilizerTask::copMaxVel
void copMaxVel(const sva::MotionVecd &copMaxVel) noexcept
Definition: StabilizerTask.h:567
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPass_
mc_filter::LowPass< Eigen::Vector3d > comOffsetLowPass_
Definition: StabilizerTask.h:948
ZMPCC.h
mc_tasks::MetaTask
Represents a generic task.
Definition: MetaTask.h:39
mc_tasks::lipm_stabilizer::StabilizerTask::externalWrenchConfiguration
void externalWrenchConfiguration(const ExternalWrenchConfiguration &extWrenchConfig) noexcept
Changes the parameters for the external wrenches.
Definition: StabilizerTask.h:643
mc_tasks::lipm_stabilizer::StabilizerTask::dcmBiasEstimatorConfiguration
const DCMBiasEstimatorConfiguration & dcmBiasEstimatorConfiguration() const noexcept
Get parameters of the DCM bias estimator.
Definition: StabilizerTask.h:636
mc_tasks::lipm_stabilizer::StabilizerTask::measuredCoMd
const Eigen::Vector3d & measuredCoMd() noexcept
Definition: StabilizerTask.h:421
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetDerivator_
mc_filter::StationaryOffset< Eigen::Vector3d > comOffsetDerivator_
Definition: StabilizerTask.h:951
mc_tasks::lipm_stabilizer::StabilizerTask::copVelFilterGain
void copVelFilterGain(double gain) noexcept
Definition: StabilizerTask.h:578
mc_filter::LowPassCompose< Eigen::Vector3d >
mc_tasks::lipm_stabilizer::StabilizerTask::copAdmittance
void copAdmittance(const Eigen::Vector2d &copAdmittance) noexcept
Definition: StabilizerTask.h:561
mc_tasks::lipm_stabilizer::StabilizerTask::dcmGains
void dcmGains(double p, double i, double d) noexcept
Definition: StabilizerTask.h:481
mc_tasks::lipm_stabilizer::StabilizerTask::dcmBiasEstimatorConfiguration
void dcmBiasEstimatorConfiguration(const DCMBiasEstimatorConfiguration &biasConfig) noexcept
Changes the parameters of the DCM bias estimator.
Definition: StabilizerTask.h:625
MC_TASKS_DLLAPI
#define MC_TASKS_DLLAPI
Definition: api.h:50
mc_tasks::lipm_stabilizer::StabilizerTask::contactWeight
void contactWeight(double weight) noexcept
Definition: StabilizerTask.h:543
mc_tasks::lipm_stabilizer::StabilizerTask::dcmIntegrator_
mc_filter::ExponentialMovingAverage< Eigen::Vector3d > dcmIntegrator_
Definition: StabilizerTask.h:954
ExponentialMovingAverage.h
mc_tasks::lipm_stabilizer::StabilizerTask::comWeight
void comWeight(double weight) noexcept
Definition: StabilizerTask.h:531
mc_tasks::lipm_stabilizer::StabilizerTask::EnumClassHash
Workaround a C++11 standard bug: no specialization of the hash functor exists for enum types....
Definition: StabilizerTask.h:850
mc_tasks::lipm_stabilizer::StabilizerTask::contactStiffness
void contactStiffness(const sva::MotionVecd &stiffness) noexcept
Definition: StabilizerTask.h:549
mc_solver::QPSolver
Definition: QPSolver.h:85
mc_tasks::lipm_stabilizer::StabilizerTask::ExternalWrench::target
EIGEN_MAKE_ALIGNED_OPERATOR_NEW sva::ForceVecd target
Target (expected) external wrench.
Definition: StabilizerTask.h:65
mc_tasks::lipm_stabilizer::StabilizerTask::comTask
std::shared_ptr< mc_tasks::CoMTask > comTask
Definition: StabilizerTask.h:872
mc_tasks::lipm_stabilizer::FDQPWeights
mc_rbdyn::lipm_stabilizer::FDQPWeights FDQPWeights
Definition: StabilizerTask.h:38
OrientationTask.h
mc_tasks::lipm_stabilizer::StabilizerTask::supportFoot
ContactState supportFoot() const noexcept
Definition: StabilizerTask.h:354
CoPTask.h
mc_tasks::lipm_stabilizer::StabilizerTask::lastConfig_
StabilizerConfiguration lastConfig_
Definition: StabilizerTask.h:896
mc_rbdyn::Robot
Definition: Robot.h:62
mc_tasks::lipm_stabilizer::StabilizerTask::fdqpWeights
void fdqpWeights(const FDQPWeights &fdqp) noexcept
Definition: StabilizerTask.h:601
mc_tasks::lipm_stabilizer::StabilizerTask::extWrenchSumLowPass_
mc_filter::LowPass< sva::ForceVecd > extWrenchSumLowPass_
Definition: StabilizerTask.h:947
mc_tasks::lipm_stabilizer::StabilizerTask::name
void name(const std::string &name) override
Definition: StabilizerTask.h:113
mc_rbdyn::lipm_stabilizer::ZMPCCConfiguration
Definition: ZMPCCConfiguration.h:14
mc_tasks::lipm_stabilizer::StabilizerTask::safetyThresholds
void safetyThresholds(const SafetyThresholds &thresholds) noexcept
Changes the safety thresholds.
Definition: StabilizerTask.h:612
mc_tasks::lipm_stabilizer::StabilizerTask::filteredDCM
Eigen::Vector2d filteredDCM() const noexcept
Definition: StabilizerTask.h:411
mc_tasks::lipm_stabilizer::StabilizerTask::torsoWeight
void torsoWeight(double weight) noexcept
Definition: StabilizerTask.h:457
mc_tasks::lipm_stabilizer::StabilizerTask::ExternalWrench::gain
sva::MotionVecd gain
Gain of measured external wrench.
Definition: StabilizerTask.h:69
mc_tasks::lipm_stabilizer::StabilizerTask::vdcStiffness
void vdcStiffness(double stiffness) noexcept
Definition: StabilizerTask.h:589
mc_tasks::lipm_stabilizer::StabilizerTask::measuredZMP
const Eigen::Vector3d & measuredZMP() noexcept
Definition: StabilizerTask.h:417
mc_rbdyn::lipm_stabilizer::DCMBiasEstimatorConfiguration
Definition: StabilizerConfiguration.h:167
mc_tasks::lipm_stabilizer::StabilizerTask::addContacts_
std::vector< ContactState > addContacts_
Definition: StabilizerTask.h:864
mc_tasks::lipm_stabilizer::StabilizerTask::ExternalWrench::surfaceName
std::string surfaceName
Name of the surface to which the external wrench is applied.
Definition: StabilizerTask.h:71
StabilizerConfiguration.h
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetTarget
const Eigen::Vector3d & comOffsetTarget() noexcept
Definition: StabilizerTask.h:425
mc_tasks::lipm_stabilizer::StabilizerTask::omega
double omega() const
Definition: StabilizerTask.h:455
mc_tasks::lipm_stabilizer::StabilizerTask::horizonZmpRef_
std::vector< Eigen::Vector2d > horizonZmpRef_
Definition: StabilizerTask.h:974
mc_tasks::lipm_stabilizer::StabilizerTask::c_
StabilizerConfiguration c_
Definition: StabilizerTask.h:900
mc_tasks::lipm_stabilizer::StabilizerTask::biasDCM
const Eigen::Vector2d biasDCM() noexcept
Definition: StabilizerTask.h:405
Contact.h
mc_tasks::lipm_stabilizer::ZMPCCConfiguration
mc_rbdyn::lipm_stabilizer::ZMPCCConfiguration ZMPCCConfiguration
Definition: StabilizerTask.h:36
mc_tasks::lipm_stabilizer::StabilizerTask::comStiffness
void comStiffness(const Eigen::Vector3d &stiffness) noexcept
Definition: StabilizerTask.h:537
mc_tasks::lipm_stabilizer::StabilizerTask::targetCoMRaw
const Eigen::Vector3d & targetCoMRaw() const noexcept
Return the raw CoM target as provided by target().
Definition: StabilizerTask.h:330
mc_tasks::lipm_stabilizer::StabilizerTask::measuredDCM
const Eigen::Vector3d & measuredDCM() noexcept
Definition: StabilizerTask.h:403
mc_tasks::lipm_stabilizer::StabilizerTask::extWrenches_
std::vector< ExternalWrench > extWrenches_
Definition: StabilizerTask.h:936
mc_rtc::Logger
Logs controller data to disk.
Definition: Logger.h:29
LeakyIntegrator.h
mc_tasks::lipm_stabilizer::StabilizerTask::contactTasks
std::vector< std::shared_ptr< mc_tasks::force::CoPTask > > contactTasks
Definition: StabilizerTask.h:866
mc_tasks::lipm_stabilizer::StabilizerTask::footTasks
std::unordered_map< ContactState, std::shared_ptr< mc_tasks::force::CoPTask >, EnumClassHash > footTasks
Definition: StabilizerTask.h:865
mc_tasks::lipm_stabilizer::StabilizerTask::dcmDerivator_
mc_filter::LowPassCompose< Eigen::Vector3d > dcmDerivator_
Definition: StabilizerTask.h:955
mc_tasks::lipm_stabilizer::SafetyThresholds
mc_rbdyn::lipm_stabilizer::SafetyThresholds SafetyThresholds
Definition: StabilizerTask.h:39
mc_tasks::lipm_stabilizer::StabilizerTask::disableConfig_
StabilizerConfiguration disableConfig_
Definition: StabilizerTask.h:898
mc_tasks::lipm_stabilizer::StabilizerTask::footSurface
const std::string & footSurface(ContactState s) const
Definition: StabilizerTask.h:263
mc_tasks::lipm_stabilizer::StabilizerTask::externalWrenchConfiguration
const ExternalWrenchConfiguration & externalWrenchConfiguration() const noexcept
Get the parameters for the external wrenches.
Definition: StabilizerTask.h:653
mc_tasks::lipm_stabilizer::StabilizerTask::ExternalWrench::measured
sva::ForceVecd measured
Measured external wrench.
Definition: StabilizerTask.h:67
mc_tasks::lipm_stabilizer::StabilizerTask::realRobot
const mc_rbdyn::Robot & realRobot() const noexcept
Definition: StabilizerTask.h:437
mc_tasks::lipm_stabilizer::StabilizerTask
Definition: StabilizerTask.h:56
mc_tasks::lipm_stabilizer::StabilizerTask::robotIndex_
unsigned int robotIndex_
Definition: StabilizerTask.h:877
mc_tasks::lipm_stabilizer::ZMPCC
Definition: ZMPCC.h:30
mc_filter::LowPass< sva::ForceVecd >
mc_tasks::lipm_stabilizer::StabilizerTask::EnumClassHash::operator()
std::size_t operator()(T t) const
Definition: StabilizerTask.h:853
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetDerivatorTimeConstant
void comOffsetDerivatorTimeConstant(double timeConstant) noexcept
Definition: StabilizerTask.h:525
mc_rtc::gui::StateBuilder
Definition: StateBuilder.h:27
mc_tasks::lipm_stabilizer::StabilizerTask::leftFootRatio
double leftFootRatio() const noexcept
Interpolation paremeter between left and right foot.
Definition: StabilizerTask.h:270
mc_tasks::lipm_stabilizer::StabilizerTask::inContact
bool inContact(ContactState state) const noexcept
Definition: StabilizerTask.h:431
mc_tasks::lipm_stabilizer::StabilizerTask::externalWrenches
const std::vector< ExternalWrench > & externalWrenches() const noexcept
Definition: StabilizerTask.h:396
mc_tasks::lipm_stabilizer::StabilizerTask::contactAnklePose
const sva::PTransformd & contactAnklePose(ContactState s) const
Projected pose of the ankle frame in the contact frame.
Definition: StabilizerTask.h:261
mc_tasks::lipm_stabilizer::StabilizerTask::ExternalWrench
External wrench.
Definition: StabilizerTask.h:61
mc_tasks::lipm_stabilizer::StabilizerTask::dcmEstimator_
stateObservation::LipmDcmEstimator dcmEstimator_
Definition: StabilizerTask.h:927
mc_rbdyn::lipm_stabilizer::SafetyThresholds
Stabilizer safety thresholds.
Definition: StabilizerConfiguration.h:98
mc_tasks::lipm_stabilizer::StabilizerTask::robot
const mc_rbdyn::Robot & robot() const noexcept
Definition: StabilizerTask.h:435
mc_filter::utils::clamp
double clamp(double value, double lower, double upper)
Definition: clamp.h:29
mc_tasks::lipm_stabilizer::StabilizerTask::torsoTask
std::shared_ptr< mc_tasks::OrientationTask > torsoTask
Definition: StabilizerTask.h:874
mc_tasks::lipm_stabilizer::StabilizerTask::robots_
const mc_rbdyn::Robots & robots_
Definition: StabilizerTask.h:875
mc_tasks::MetaTask::name
const std::string & name() const
Definition: MetaTask.h:67
deprecated.h
mc_tasks::lipm_stabilizer::StabilizerTask::extWrenchSumLowPassCutoffPeriod
void extWrenchSumLowPassCutoffPeriod(double cutoffPeriod) noexcept
Definition: StabilizerTask.h:507
mc_tasks::lipm_stabilizer::StabilizerTask::supportFoot
void supportFoot(const ContactState &foot) noexcept
Definition: StabilizerTask.h:357
mc_rbdyn::lipm_stabilizer::ExternalWrenchConfiguration
Parameters for the external wrenches.
Definition: StabilizerConfiguration.h:260
mc_tasks::lipm_stabilizer::StabilizerTask::fSumFilter_
mc_filter::LowPass< Eigen::Vector3d > fSumFilter_
Definition: StabilizerTask.h:998
mc_tasks::lipm_stabilizer::StabilizerTask::zmpCoeffMeasured
double zmpCoeffMeasured() const noexcept
Definition: StabilizerTask.h:429
mc_tasks::lipm_stabilizer::StabilizerTask::torsoPitch
void torsoPitch(double pitch) noexcept
Definition: StabilizerTask.h:453
mc_tasks::lipm_stabilizer::StabilizerTask::qpSolver_
Eigen::QuadProgDense qpSolver_
Definition: StabilizerTask.h:906
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPassCoM_
mc_filter::LowPass< Eigen::Vector3d > comOffsetLowPassCoM_
Definition: StabilizerTask.h:950
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetLowPassCutoffPeriod
void comOffsetLowPassCutoffPeriod(double cutoffPeriod) noexcept
Definition: StabilizerTask.h:513
mc_tasks::lipm_stabilizer::StabilizerTask::realRobots_
const mc_rbdyn::Robots & realRobots_
Definition: StabilizerTask.h:876
mc_rbdyn::lipm_stabilizer::FDQPWeights
Definition: StabilizerConfiguration.h:22
mc_tasks::lipm_stabilizer::StabilizerTask::measuredFilteredNetForces
const Eigen::Vector3d & measuredFilteredNetForces() const noexcept
Definition: StabilizerTask.h:423
mc_tasks::lipm_stabilizer::StabilizerTask::supportPolygons_
std::vector< std::vector< Eigen::Vector3d > > supportPolygons_
Definition: StabilizerTask.h:869
mc_tasks::lipm_stabilizer::StabilizerTask::targetZMPVelocity
const Eigen::Vector3d & targetZMPVelocity() const noexcept
Definition: StabilizerTask.h:351
CoMTask.h
mc_tasks::lipm_stabilizer::StabilizerTask::torsoStiffness
void torsoStiffness(double stiffness) noexcept
Definition: StabilizerTask.h:463
mc_tasks::lipm_stabilizer::StabilizerTask::dfDamping
void dfDamping(Eigen::Vector3d dfDamping) noexcept
Definition: StabilizerTask.h:596
mc_control::fsm::Contact
mc_control::Contact Contact
Definition: Controller.h:22
mc_tasks::lipm_stabilizer::StabilizerTask::contactSensors
std::vector< std::string > contactSensors
Definition: StabilizerTask.h:867
mc_tasks::lipm_stabilizer::StabilizerTask::copVelFilterGain
double copVelFilterGain() const noexcept
Definition: StabilizerTask.h:585
StationaryOffset.h
mc_tasks::lipm_stabilizer::StabilizerTask::pelvisWeight
void pelvisWeight(double weight) noexcept
Definition: StabilizerTask.h:469
mc_rbdyn::lipm_stabilizer::StabilizerConfiguration
Configuration of the LIPMStabilizer. This configuration is meant to be overriden from the RobotModule...
Definition: StabilizerConfiguration.h:434
mc_tasks::lipm_stabilizer::StabilizerTask::dcmDerivatorTimeConstant
MC_RTC_DEPRECATED void dcmDerivatorTimeConstant(double T) noexcept
Definition: StabilizerTask.h:499
mc_tasks::lipm_stabilizer::StabilizerTask::targetCoMAcceleration
const Eigen::Vector3d & targetCoMAcceleration() const noexcept
Definition: StabilizerTask.h:345
mc_tasks::lipm_stabilizer::StabilizerTask::comOffsetMeasured
const Eigen::Vector3d & comOffsetMeasured() const noexcept
Definition: StabilizerTask.h:427
MetaTask.h
mc_tasks::lipm_stabilizer::StabilizerTask::pelvisTask
std::shared_ptr< mc_tasks::OrientationTask > pelvisTask
Definition: StabilizerTask.h:873
mc_tasks::lipm_stabilizer::StabilizerTask::targetCoMVelocity
const Eigen::Vector3d & targetCoMVelocity() const noexcept
Definition: StabilizerTask.h:342
mc_tasks::lipm_stabilizer::DCMBiasEstimatorConfiguration
mc_rbdyn::lipm_stabilizer::DCMBiasEstimatorConfiguration DCMBiasEstimatorConfiguration
Definition: StabilizerTask.h:40
mc_tasks::lipm_stabilizer::StabilizerTask::distribZMP
const Eigen::Vector3d & distribZMP() const noexcept
Definition: StabilizerTask.h:401
mc_tasks::lipm_stabilizer::StabilizerTask::targetZMP
const Eigen::Vector3d & targetZMP() const noexcept
Definition: StabilizerTask.h:348
mc_tasks::lipm_stabilizer::StabilizerTask::inDoubleSupport
bool inDoubleSupport() const noexcept
Definition: StabilizerTask.h:433
mc_tasks::lipm_stabilizer::StabilizerTask::dcmDerivatorCutoffPeriod
void dcmDerivatorCutoffPeriod(double T) noexcept
Definition: StabilizerTask.h:501
mc_tasks::lipm_stabilizer::StabilizerTask::pelvisStiffness
void pelvisStiffness(double stiffness) noexcept
Definition: StabilizerTask.h:475
mc_tasks
Definition: StabilizerStandingState.h:11
Left
Left
Definition: types.h:158
mc_filter::ExponentialMovingAverage< Eigen::Vector3d >
mc_filter::StationaryOffset< Eigen::Vector3d >
mc_tasks::lipm_stabilizer::StabilizerConfiguration
mc_rbdyn::lipm_stabilizer::StabilizerConfiguration StabilizerConfiguration
Definition: StabilizerTask.h:37
LowPass.h
mc_tasks::lipm_stabilizer::StabilizerTask::dcmGains
void dcmGains(const Eigen::Vector2d &p, const Eigen::Vector2d &i, const Eigen::Vector2d &d) noexcept
Definition: StabilizerTask.h:486
mc_tasks::lipm_stabilizer::StabilizerTask::defaultConfig_
StabilizerConfiguration defaultConfig_
Definition: StabilizerTask.h:894
mc_tasks::lipm_stabilizer::StabilizerTask::contactDamping
void contactDamping(const sva::MotionVecd &damping) noexcept
Definition: StabilizerTask.h:555
mc_tasks::lipm_stabilizer::StabilizerTask::dfAdmittance
void dfAdmittance(Eigen::Vector3d dfAdmittance) noexcept
Definition: StabilizerTask.h:591