25 struct MultiBodyConfig;
41 const Eigen::VectorXd & dimWeight,
44 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(alphaDBegin_, alphaDBegin_); }
48 const Eigen::VectorXd &
dimWeight()
const {
return dimWeight_; }
52 virtual const Eigen::MatrixXd &
Q()
const override;
53 virtual const Eigen::VectorXd &
C()
const override;
63 Eigen::VectorXd dimWeight_;
64 int robotIndex_, alphaDBegin_;
69 Eigen::MatrixXd preQ_;
70 Eigen::VectorXd preC_;
86 const Eigen::VectorXd & dimWeight,
93 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
94 const std::vector<rbd::MultiBodyConfig> & mbcs,
98 double stiffness_, stiffnessSqrt_;
116 const Eigen::VectorXd & dimWeight,
125 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
126 const std::vector<rbd::MultiBodyConfig> & mbcs,
130 double gainPos_, gainVel_;
131 Eigen::VectorXd errorPos_, errorVel_, refAccel_;
149 const Eigen::VectorXd & dimWeight,
153 void setGains(
const Eigen::VectorXd & stiffness,
const Eigen::VectorXd & damping);
158 void damping(
const Eigen::VectorXd & damping);
161 void refVel(
const Eigen::VectorXd & refVel);
166 void update(
const std::vector<rbd::MultiBody> & mbs,
167 const std::vector<rbd::MultiBodyConfig> & mbcs,
171 Eigen::VectorXd stiffness_, damping_;
172 Eigen::VectorXd refVel_, refAccel_;
179 PIDTask(
const std::vector<rbd::MultiBody> & mbs,
187 PIDTask(
const std::vector<rbd::MultiBody> & mbs,
193 const Eigen::VectorXd & dimWeight,
203 void error(
const Eigen::VectorXd & err);
204 void errorD(
const Eigen::VectorXd & errD);
205 void errorI(
const Eigen::VectorXd & errI);
207 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
208 const std::vector<rbd::MultiBodyConfig> & mbcs,
213 Eigen::VectorXd error_, errorD_, errorI_;
224 const Eigen::VectorXd & objDot,
232 const Eigen::VectorXd & objDot,
233 const Eigen::VectorXd & dimWeight,
239 int iter()
const {
return iter_; }
240 void iter(
int i) { iter_ = i; }
245 const Eigen::VectorXd &
objDot()
const {
return objDot_; }
246 void objDot(
const Eigen::VectorXd & o) { objDot_ = o; }
248 const Eigen::VectorXd &
dimWeight()
const {
return dimWeight_; }
249 void dimWeight(
const Eigen::VectorXd & o) { dimWeight_ = o; }
251 const Eigen::VectorXd &
phi()
const {
return phi_; }
252 const Eigen::VectorXd &
psi()
const {
return psi_; }
254 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(alphaDBegin_, alphaDBegin_); }
257 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
258 const std::vector<rbd::MultiBodyConfig> & mbcs,
261 virtual const Eigen::MatrixXd &
Q()
const override;
262 virtual const Eigen::VectorXd &
C()
const override;
269 Eigen::VectorXd objDot_;
270 Eigen::VectorXd dimWeight_;
271 int robotIndex_, alphaDBegin_;
273 Eigen::VectorXd phi_, psi_;
278 Eigen::MatrixXd preQ_;
279 Eigen::VectorXd CVecSum_, preC_;
288 const std::vector<std::string> & activeJointsName,
289 const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {});
293 const std::vector<std::string> & unactiveJointsName,
294 const std::map<std::string, std::vector<std::array<int, 2>>> & unactiveDofs = {});
306 const std::vector<std::string> & selectedJointsName,
307 const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {});
309 const std::vector<SelectedData>
selectedJoints()
const {
return selectedJoints_; }
311 virtual int dim()
override;
312 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
313 const std::vector<rbd::MultiBodyConfig> & mbcs,
316 virtual const Eigen::MatrixXd &
jac()
const override;
317 virtual const Eigen::VectorXd &
eval()
const override;
318 virtual const Eigen::VectorXd &
speed()
const override;
319 virtual const Eigen::VectorXd &
normalAcc()
const override;
322 Eigen::MatrixXd jac_;
323 std::vector<SelectedData> selectedJoints_;
341 damping = 2. * std::sqrt(stif);
358 const Eigen::VectorXd & jointSelect,
364 const std::string & efName,
379 const Eigen::VectorXd & jointSelect,
387 const std::string & efName,
391 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
392 const std::vector<rbd::MultiBodyConfig> & mbcs,
395 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(0, 0); }
397 virtual const Eigen::MatrixXd &
Q()
const override {
return Q_; }
399 virtual const Eigen::VectorXd &
C()
const override {
return C_; }
401 virtual const Eigen::VectorXd &
jointSelect()
const {
return jointSelector_; }
405 int alphaDBegin_, lambdaBegin_;
407 Eigen::VectorXd jointSelector_;
417 std::vector<std::vector<double>> q,
423 void posture(std::vector<std::vector<double>> q) { pt_.posture(q); }
425 const std::vector<std::vector<double>>
posture()
const {
return pt_.posture(); }
434 void gains(
double stiffness,
double damping);
436 void jointsStiffness(
const std::vector<rbd::MultiBody> & mbs,
const std::vector<JointStiffness> & jsv);
438 void jointsGains(
const std::vector<rbd::MultiBody> & mbs,
const std::vector<JointGains> & jgv);
440 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(alphaDBegin_, alphaDBegin_); }
443 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
444 const std::vector<rbd::MultiBodyConfig> & mbcs,
447 virtual const Eigen::MatrixXd &
Q()
const override;
448 virtual const Eigen::VectorXd &
C()
const override;
450 const Eigen::VectorXd &
eval()
const;
452 inline void refVel(
const Eigen::VectorXd & refVel) noexcept { refVel_ =
refVel; }
453 inline const Eigen::VectorXd &
refVel() const noexcept {
return refVel_; }
454 inline void refAccel(
const Eigen::VectorXd & refAccel) noexcept
456 assert(refAccel.size() == refAccel_.size());
457 refAccel_ = refAccel;
459 inline const Eigen::VectorXd &
refAccel() const noexcept {
return refAccel_; }
461 inline const Eigen::VectorXd &
dimWeight() const noexcept {
return dimWeight_; }
463 inline void dimWeight(
const Eigen::VectorXd & dimW) noexcept
465 assert(dimW.size() == dimWeight_.size());
472 double stiffness, damping;
481 int robotIndex_, alphaDBegin_;
483 std::vector<JointData> jointDatas_;
487 Eigen::VectorXd alphaVec_;
488 Eigen::VectorXd refVel_, refAccel_;
489 Eigen::VectorXd dimWeight_;
497 const std::string & bodyName,
498 const Eigen::Vector3d & pos,
499 const Eigen::Vector3d & bodyPoint = Eigen::Vector3d::Zero());
503 void position(
const Eigen::Vector3d & pos) { pt_.position(pos); }
505 const Eigen::Vector3d &
position()
const {
return pt_.position(); }
507 void bodyPoint(
const Eigen::Vector3d & point) { pt_.bodyPoint(point); }
509 const Eigen::Vector3d &
bodyPoint()
const {
return pt_.bodyPoint(); }
511 virtual int dim()
override;
512 virtual void update(
const std::vector<rbd::MultiBody> & mb,
513 const std::vector<rbd::MultiBodyConfig> & mbc,
516 virtual const Eigen::MatrixXd &
jac()
const override;
517 virtual const Eigen::VectorXd &
eval()
const override;
518 virtual const Eigen::VectorXd &
speed()
const override;
519 virtual const Eigen::VectorXd &
normalAcc()
const override;
531 const std::string & bodyName,
532 const Eigen::Quaterniond & ori);
535 const std::string & bodyName,
536 const Eigen::Matrix3d & ori);
540 void orientation(
const Eigen::Quaterniond & ori) { ot_.orientation(ori); }
542 void orientation(
const Eigen::Matrix3d & ori) { ot_.orientation(ori); }
544 const Eigen::Matrix3d &
orientation()
const {
return ot_.orientation(); }
546 virtual int dim()
override;
547 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
548 const std::vector<rbd::MultiBodyConfig> & mbcs,
551 virtual const Eigen::MatrixXd &
jac()
const override;
552 virtual const Eigen::VectorXd &
eval()
const override;
553 virtual const Eigen::VectorXd &
speed()
const override;
554 virtual const Eigen::VectorXd &
normalAcc()
const override;
561 template<
typename transform_task_t>
567 const std::string & bodyName,
568 const sva::PTransformd & X_0_t,
569 const sva::PTransformd &
X_b_p = sva::PTransformd::Identity())
576 void target(
const sva::PTransformd & X_0_t) {
tt_.target(X_0_t); }
578 const sva::PTransformd &
target()
const {
return tt_.target(); }
582 const sva::PTransformd &
X_b_p()
const {
return tt_.X_b_p(); }
584 virtual int dim()
override {
return 6; }
586 virtual const Eigen::MatrixXd &
jac()
const override {
return tt_.jac(); }
588 virtual const Eigen::VectorXd &
eval()
const override {
return tt_.eval(); }
590 virtual const Eigen::VectorXd &
speed()
const override {
return tt_.speed(); }
592 virtual const Eigen::VectorXd &
normalAcc()
const override {
return tt_.normalAcc(); }
605 const std::string & bodyName,
606 const sva::PTransformd & X_0_t,
607 const sva::PTransformd & X_b_p = sva::PTransformd::Identity());
609 virtual void update(
const std::vector<rbd::MultiBody> & mb,
610 const std::vector<rbd::MultiBodyConfig> & mbc,
620 const std::string & bodyName,
621 const sva::PTransformd & X_0_t,
622 const sva::PTransformd & X_b_p = sva::PTransformd::Identity(),
623 const Eigen::Matrix3d & E_0_c = Eigen::Matrix3d::Identity());
625 void E_0_c(
const Eigen::Matrix3d & E_0_c);
626 const Eigen::Matrix3d &
E_0_c()
const;
628 virtual void update(
const std::vector<rbd::MultiBody> & mb,
629 const std::vector<rbd::MultiBodyConfig> & mbc,
638 const std::string & bodyName,
639 const Eigen::Quaterniond & ori,
640 const sva::PTransformd & X_b_s);
643 const std::string & bodyName,
644 const Eigen::Matrix3d & ori,
645 const sva::PTransformd & X_b_s);
649 void orientation(
const Eigen::Quaterniond & ori) { ot_.orientation(ori); }
651 void orientation(
const Eigen::Matrix3d & ori) { ot_.orientation(ori); }
653 const Eigen::Matrix3d &
orientation()
const {
return ot_.orientation(); }
655 virtual int dim()
override;
656 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
657 const std::vector<rbd::MultiBodyConfig> & mbcs,
660 virtual const Eigen::MatrixXd &
jac()
const override;
661 virtual const Eigen::VectorXd &
eval()
const override;
662 virtual const Eigen::VectorXd &
speed()
const override;
663 virtual const Eigen::VectorXd &
normalAcc()
const override;
675 const std::string & bodyName,
676 const Eigen::Vector2d & point2d,
677 double depthEstimate,
678 const sva::PTransformd & X_b_gaze,
679 const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero());
682 const std::string & bodyName,
683 const Eigen::Vector3d & point3d,
684 const sva::PTransformd & X_b_gaze,
685 const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero());
689 void error(
const Eigen::Vector2d & point2d,
const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero())
691 gazet_.error(point2d, point2d_ref);
694 void error(
const Eigen::Vector3d & point3d,
const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero())
696 gazet_.error(point3d, point2d_ref);
699 virtual int dim()
override;
700 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
701 const std::vector<rbd::MultiBodyConfig> & mbcs,
704 virtual const Eigen::MatrixXd &
jac()
const override;
705 virtual const Eigen::VectorXd &
eval()
const override;
706 virtual const Eigen::VectorXd &
speed()
const override;
707 virtual const Eigen::VectorXd &
normalAcc()
const override;
719 const std::string & bodyName,
720 const sva::PTransformd & X_t_s,
721 const sva::PTransformd & X_b_s = sva::PTransformd::Identity());
725 void error(
const sva::PTransformd & X_t_s) { pbvst_.error(X_t_s); }
727 virtual int dim()
override;
728 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
729 const std::vector<rbd::MultiBodyConfig> & mbcs,
732 virtual const Eigen::MatrixXd &
jac()
const override;
733 virtual const Eigen::VectorXd &
eval()
const override;
734 virtual const Eigen::VectorXd &
speed()
const override;
735 virtual const Eigen::VectorXd &
normalAcc()
const override;
745 CoMTask(
const std::vector<rbd::MultiBody> & mbs,
int robotIndex,
const Eigen::Vector3d & com);
746 CoMTask(
const std::vector<rbd::MultiBody> & mbs,
748 const Eigen::Vector3d & com,
749 std::vector<double> weight);
753 void com(
const Eigen::Vector3d & com) { ct_.com(com); }
755 const Eigen::Vector3d &
com()
const {
return ct_.com(); }
757 const Eigen::Vector3d &
actual()
const {
return ct_.actual(); }
761 virtual int dim()
override;
762 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
763 const std::vector<rbd::MultiBodyConfig> & mbcs,
766 virtual const Eigen::MatrixXd &
jac()
const override;
767 virtual const Eigen::VectorXd &
eval()
const override;
768 virtual const Eigen::VectorXd &
speed()
const override;
769 virtual const Eigen::VectorXd &
normalAcc()
const override;
780 std::vector<int> robotIndexes,
781 const Eigen::Vector3d & com,
785 std::vector<int> robotIndexes,
786 const Eigen::Vector3d & com,
788 const Eigen::Vector3d & dimWeight,
793 void com(
const Eigen::Vector3d & com) { mct_.com(com); }
795 const Eigen::Vector3d
com()
const {
return mct_.com(); }
805 const Eigen::Vector3d &
dimWeight()
const {
return dimWeight_; }
807 virtual std::pair<int, int>
begin()
const override {
return {alphaDBegin_, alphaDBegin_}; }
810 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
811 const std::vector<rbd::MultiBodyConfig> & mbcs,
814 virtual const Eigen::MatrixXd &
Q()
const override;
815 virtual const Eigen::VectorXd &
C()
const override;
817 const Eigen::VectorXd &
eval()
const;
818 const Eigen::VectorXd &
speed()
const;
821 void init(
const std::vector<rbd::MultiBody> & mbs);
825 double stiffness_, stiffnessSqrt_;
826 Eigen::Vector3d dimWeight_;
827 std::vector<int> posInQ_;
831 Eigen::Vector3d CSum_;
833 Eigen::MatrixXd preQ_;
842 const std::string & r1BodyName,
843 const std::string & r2BodyName,
844 const sva::PTransformd & X_r1b_r1s,
845 const sva::PTransformd & X_r2b_r2s,
863 const Eigen::VectorXd &
dimWeight()
const {
return dimWeight_; }
865 virtual std::pair<int, int>
begin()
const override {
return {alphaDBegin_, alphaDBegin_}; }
868 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
869 const std::vector<rbd::MultiBodyConfig> & mbcs,
872 virtual const Eigen::MatrixXd &
Q()
const override;
873 virtual const Eigen::VectorXd &
C()
const override;
875 const Eigen::VectorXd &
eval()
const;
876 const Eigen::VectorXd &
speed()
const;
880 double stiffness_, stiffnessSqrt_;
881 Eigen::VectorXd dimWeight_;
882 std::vector<int> posInQ_, robotIndexes_;
886 Eigen::VectorXd CSum_;
888 Eigen::MatrixXd preQ_;
894 MomentumTask(
const std::vector<rbd::MultiBody> & mbs,
int robotIndex,
const sva::ForceVecd & mom);
898 void momentum(
const sva::ForceVecd & mom) { momt_.momentum(mom); }
900 const sva::ForceVecd
momentum()
const {
return momt_.momentum(); }
902 virtual int dim()
override;
903 virtual void update(
const std::vector<rbd::MultiBody> & mb,
904 const std::vector<rbd::MultiBodyConfig> & mbc,
907 virtual const Eigen::MatrixXd &
jac()
const override;
908 virtual const Eigen::VectorXd &
eval()
const override;
909 virtual const Eigen::VectorXd &
speed()
const override;
910 virtual const Eigen::VectorXd &
normalAcc()
const override;
921 :
Task(weight), contactId_(contactId), begin_(0), stiffness_(stiffness), stiffnessSqrt_(2 * std::sqrt(stiffness)),
922 conesJac_(), error_(Eigen::Vector3d::Zero()), errorD_(Eigen::Vector3d::Zero()), Q_(), C_()
926 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(begin_, begin_); }
928 void error(
const Eigen::Vector3d & error);
929 void errorD(
const Eigen::Vector3d & errorD);
932 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
933 const std::vector<rbd::MultiBodyConfig> & mbcs,
936 virtual const Eigen::MatrixXd &
Q()
const override;
937 virtual const Eigen::VectorXd &
C()
const override;
943 double stiffness_, stiffnessSqrt_;
944 Eigen::MatrixXd conesJac_;
945 Eigen::Vector3d error_, errorD_;
955 :
Task(weight), contactId_(contactId), origin_(origin), axis_(axis), begin_(0), Q_(), C_()
959 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(begin_, begin_); }
962 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
963 const std::vector<rbd::MultiBodyConfig> & mbcs,
966 virtual const Eigen::MatrixXd &
Q()
const override;
967 virtual const Eigen::VectorXd &
C()
const override;
971 Eigen::Vector3d origin_;
972 Eigen::Vector3d axis_;
984 const std::string & bodyName,
985 const Eigen::Vector3d & vel,
986 const Eigen::Vector3d & bodyPoint = Eigen::Vector3d::Zero());
990 void velocity(
const Eigen::Vector3d & s) { pt_.velocity(s); }
992 const Eigen::Vector3d &
velocity()
const {
return pt_.velocity(); }
994 void bodyPoint(
const Eigen::Vector3d & point) { pt_.bodyPoint(point); }
996 const Eigen::Vector3d &
bodyPoint()
const {
return pt_.bodyPoint(); }
998 virtual int dim()
override;
999 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1000 const std::vector<rbd::MultiBodyConfig> & mbcs,
1003 virtual const Eigen::MatrixXd &
jac()
const override;
1004 virtual const Eigen::VectorXd &
eval()
const override;
1005 virtual const Eigen::VectorXd &
speed()
const override;
1018 const std::string & bodyName,
1019 const Eigen::Vector3d & bodyPoint,
1020 const Eigen::Vector3d & bodyAxis,
1021 const std::vector<std::string> & trackingJointsName,
1022 const Eigen::Vector3d & trackedPoint);
1028 const Eigen::Vector3d &
trackedPoint()
const {
return ott_.trackedPoint(); }
1030 void bodyPoint(
const Eigen::Vector3d & bp) { ott_.bodyPoint(bp); }
1032 const Eigen::Vector3d &
bodyPoint()
const {
return ott_.bodyPoint(); }
1034 void bodyAxis(
const Eigen::Vector3d & ba) { ott_.bodyAxis(ba); }
1036 const Eigen::Vector3d &
bodyAxis()
const {
return ott_.bodyAxis(); }
1039 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1040 const std::vector<rbd::MultiBodyConfig> & mbcs,
1043 virtual const Eigen::MatrixXd &
jac()
const override;
1044 virtual const Eigen::VectorXd &
eval()
const override;
1045 virtual const Eigen::VectorXd &
speed()
const override;
1051 Eigen::VectorXd alphaVec_;
1052 Eigen::VectorXd speed_, normalAcc_;
1060 const double timestep,
1063 const Eigen::Vector3d & u1 = Eigen::Vector3d::Zero(),
1064 const Eigen::Vector3d & u2 = Eigen::Vector3d::Zero());
1068 void robotPoint(
const rbd::MultiBody & mb,
const std::string & bName,
const Eigen::Vector3d & point)
1070 int bIndex = mb.bodyIndexByName(bName);
1071 rdt_.robotPoint(bIndex, point);
1073 void envPoint(
const rbd::MultiBody & mb,
const std::string & bName,
const Eigen::Vector3d & point)
1075 int bIndex = mb.bodyIndexByName(bName);
1076 rdt_.envPoint(bIndex, point);
1078 void vector(
const rbd::MultiBody & mb,
const std::string & bName,
const Eigen::Vector3d & u)
1080 int bIndex = mb.bodyIndexByName(bName);
1081 rdt_.vector(bIndex, u);
1085 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1086 const std::vector<rbd::MultiBodyConfig> & mbcs,
1089 virtual const Eigen::MatrixXd &
jac()
const override;
1090 virtual const Eigen::VectorXd &
eval()
const override;
1091 virtual const Eigen::VectorXd &
speed()
const override;
1104 const std::string & bodyName,
1105 const Eigen::Vector3d & bodyVector,
1106 const Eigen::Vector3d & targetVector);
1109 void bodyVector(
const Eigen::Vector3d & vector) { vot_.bodyVector(vector); }
1110 const Eigen::Vector3d &
bodyVector()
const {
return vot_.bodyVector(); }
1111 void target(
const Eigen::Vector3d & vector) { vot_.target(vector); }
1112 const Eigen::Vector3d &
target()
const {
return vot_.target(); }
1113 const Eigen::Vector3d &
actual()
const {
return vot_.actual(); }
1116 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1117 const std::vector<rbd::MultiBodyConfig> & mbcs,
1120 virtual const Eigen::MatrixXd &
jac()
const override;
1121 virtual const Eigen::VectorXd &
eval()
const override;
1122 virtual const Eigen::VectorXd &
speed()
const override;
std::tuple< std::string, Eigen::Vector3d, Eigen::Vector3d > rbInfo
Definition: Tasks.h:599
Definition: QPTasks.h:743
void com(const Eigen::Vector3d &com)
Definition: QPTasks.h:753
virtual const Eigen::VectorXd & eval() const override
const Eigen::Vector3d & com() const
Definition: QPTasks.h:755
virtual const Eigen::MatrixXd & jac() const override
CoMTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const Eigen::Vector3d &com)
const Eigen::Vector3d & actual() const
Definition: QPTasks.h:757
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
CoMTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const Eigen::Vector3d &com, std::vector< double > weight)
tasks::CoMTask & task()
Definition: QPTasks.h:751
void updateInertialParameters(const std::vector< rbd::MultiBody > &mbs)
virtual const Eigen::VectorXd & normalAcc() const override
virtual int dim() override
virtual const Eigen::VectorXd & speed() const override
Definition: QPTasks.h:671
GazeTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const Eigen::Vector2d &point2d, double depthEstimate, const sva::PTransformd &X_b_gaze, const Eigen::Vector2d &point2d_ref=Eigen::Vector2d::Zero())
GazeTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const Eigen::Vector3d &point3d, const sva::PTransformd &X_b_gaze, const Eigen::Vector2d &point2d_ref=Eigen::Vector2d::Zero())
virtual int dim() override
void error(const Eigen::Vector2d &point2d, const Eigen::Vector2d &point2d_ref=Eigen::Vector2d::Zero())
Definition: QPTasks.h:689
virtual const Eigen::VectorXd & normalAcc() const override
virtual const Eigen::VectorXd & eval() const override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
virtual const Eigen::VectorXd & speed() const override
void error(const Eigen::Vector3d &point3d, const Eigen::Vector2d &point2d_ref=Eigen::Vector2d::Zero())
Definition: QPTasks.h:694
tasks::GazeTask & task()
Definition: QPTasks.h:687
virtual const Eigen::MatrixXd & jac() const override
Definition: QPTasks.h:952
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:959
virtual const Eigen::VectorXd & C() const override
virtual const Eigen::MatrixXd & Q() const override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
GripperTorqueTask(ContactId contactId, const Eigen::Vector3d &origin, const Eigen::Vector3d &axis, double weight)
Definition: QPTasks.h:954
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
Definition: QPSolver.h:303
Definition: QPTasks.h:283
virtual const Eigen::VectorXd & normalAcc() const override
virtual const Eigen::VectorXd & eval() const override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
static JointsSelector UnactiveJoints(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hl, const std::vector< std::string > &unactiveJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &unactiveDofs={})
const std::vector< SelectedData > selectedJoints() const
Definition: QPTasks.h:309
virtual const Eigen::VectorXd & speed() const override
virtual const Eigen::MatrixXd & jac() const override
JointsSelector(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hl, const std::vector< std::string > &selectedJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &activeDofs={})
virtual int dim() override
static JointsSelector ActiveJoints(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hl, const std::vector< std::string > &activeJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &activeDofs={})
Definition: QPTasks.h:980
virtual const Eigen::VectorXd & eval() const override
virtual const Eigen::VectorXd & speed() const override
const Eigen::Vector3d & bodyPoint() const
Definition: QPTasks.h:996
virtual const Eigen::MatrixXd & jac() const override
virtual int dim() override
const Eigen::Vector3d & velocity() const
Definition: QPTasks.h:992
tasks::LinVelocityTask & task()
Definition: QPTasks.h:988
void velocity(const Eigen::Vector3d &s)
Definition: QPTasks.h:990
void bodyPoint(const Eigen::Vector3d &point)
Definition: QPTasks.h:994
virtual const Eigen::VectorXd & normalAcc() const override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
LinVelocityTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const Eigen::Vector3d &vel, const Eigen::Vector3d &bodyPoint=Eigen::Vector3d::Zero())
Definition: QPTasks.h:892
virtual const Eigen::VectorXd & eval() const override
virtual const Eigen::VectorXd & normalAcc() const override
const sva::ForceVecd momentum() const
Definition: QPTasks.h:900
virtual int dim() override
tasks::MomentumTask & task()
Definition: QPTasks.h:896
void momentum(const sva::ForceVecd &mom)
Definition: QPTasks.h:898
virtual void update(const std::vector< rbd::MultiBody > &mb, const std::vector< rbd::MultiBodyConfig > &mbc, const SolverData &data) override
virtual const Eigen::MatrixXd & jac() const override
virtual const Eigen::VectorXd & speed() const override
MomentumTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const sva::ForceVecd &mom)
Definition: QPMotionConstr.h:123
Definition: QPTasks.h:777
void updateInertialParameters(const std::vector< rbd::MultiBody > &mbs)
void com(const Eigen::Vector3d &com)
Definition: QPTasks.h:793
virtual const Eigen::MatrixXd & Q() const override
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:807
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
void stiffness(double stiffness)
MultiCoMTask(const std::vector< rbd::MultiBody > &mb, std::vector< int > robotIndexes, const Eigen::Vector3d &com, double stiffness, double weight)
tasks::MultiCoMTask & task()
Definition: QPTasks.h:791
const Eigen::Vector3d com() const
Definition: QPTasks.h:795
double stiffness() const
Definition: QPTasks.h:799
const Eigen::VectorXd & eval() const
void dimWeight(const Eigen::Vector3d &dim)
virtual const Eigen::VectorXd & C() const override
const Eigen::Vector3d & dimWeight() const
Definition: QPTasks.h:805
MultiCoMTask(const std::vector< rbd::MultiBody > &mb, std::vector< int > robotIndexes, const Eigen::Vector3d &com, double stiffness, const Eigen::Vector3d &dimWeight, double weight)
const Eigen::VectorXd & speed() const
Definition: QPTasks.h:527
OrientationTask(const std::vector< rbd::MultiBody > &mbs, int robodIndex, const std::string &bodyName, const Eigen::Matrix3d &ori)
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
const Eigen::Matrix3d & orientation() const
Definition: QPTasks.h:544
virtual const Eigen::VectorXd & speed() const override
virtual int dim() override
virtual const Eigen::VectorXd & eval() const override
OrientationTask(const std::vector< rbd::MultiBody > &mbs, int robodIndex, const std::string &bodyName, const Eigen::Quaterniond &ori)
void orientation(const Eigen::Quaterniond &ori)
Definition: QPTasks.h:540
void orientation(const Eigen::Matrix3d &ori)
Definition: QPTasks.h:542
virtual const Eigen::MatrixXd & jac() const override
tasks::OrientationTask & task()
Definition: QPTasks.h:538
virtual const Eigen::VectorXd & normalAcc() const override
Definition: QPTasks.h:1014
virtual const Eigen::VectorXd & normalAcc() const override
void trackedPoint(const Eigen::Vector3d &tp)
Definition: QPTasks.h:1026
const Eigen::Vector3d & bodyPoint() const
Definition: QPTasks.h:1032
const Eigen::Vector3d & trackedPoint() const
Definition: QPTasks.h:1028
virtual const Eigen::VectorXd & eval() const override
OrientationTrackingTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const Eigen::Vector3d &bodyPoint, const Eigen::Vector3d &bodyAxis, const std::vector< std::string > &trackingJointsName, const Eigen::Vector3d &trackedPoint)
void bodyAxis(const Eigen::Vector3d &ba)
Definition: QPTasks.h:1034
const Eigen::Vector3d & bodyAxis() const
Definition: QPTasks.h:1036
virtual const Eigen::VectorXd & speed() const override
void bodyPoint(const Eigen::Vector3d &bp)
Definition: QPTasks.h:1030
virtual int dim() override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
virtual const Eigen::MatrixXd & jac() const override
tasks::OrientationTrackingTask & task()
Definition: QPTasks.h:1024
Definition: QPTasks.h:177
void errorI(const Eigen::VectorXd &errI)
void error(const Eigen::VectorXd &err)
PIDTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double P, double I, double D, double weight)
PIDTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double P, double I, double D, const Eigen::VectorXd &dimWeight, double weight)
void errorD(const Eigen::VectorXd &errD)
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
Definition: QPTasks.h:715
tasks::PositionBasedVisServoTask & task()
Definition: QPTasks.h:723
void error(const sva::PTransformd &X_t_s)
Definition: QPTasks.h:725
PositionBasedVisServoTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const sva::PTransformd &X_t_s, const sva::PTransformd &X_b_s=sva::PTransformd::Identity())
virtual const Eigen::VectorXd & eval() const override
virtual const Eigen::VectorXd & speed() const override
virtual int dim() override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
virtual const Eigen::MatrixXd & jac() const override
virtual const Eigen::VectorXd & normalAcc() const override
Definition: QPTasks.h:493
virtual void update(const std::vector< rbd::MultiBody > &mb, const std::vector< rbd::MultiBodyConfig > &mbc, const SolverData &data) override
const Eigen::Vector3d & bodyPoint() const
Definition: QPTasks.h:509
PositionTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const Eigen::Vector3d &pos, const Eigen::Vector3d &bodyPoint=Eigen::Vector3d::Zero())
void bodyPoint(const Eigen::Vector3d &point)
Definition: QPTasks.h:507
tasks::PositionTask & task()
Definition: QPTasks.h:501
const Eigen::Vector3d & position() const
Definition: QPTasks.h:505
virtual int dim() override
void position(const Eigen::Vector3d &pos)
Definition: QPTasks.h:503
virtual const Eigen::MatrixXd & jac() const override
virtual const Eigen::VectorXd & normalAcc() const override
virtual const Eigen::VectorXd & eval() const override
virtual const Eigen::VectorXd & speed() const override
Definition: QPTasks.h:413
PostureTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, std::vector< std::vector< double >> q, double stiffness, double weight)
const Eigen::VectorXd & refAccel() const noexcept
Definition: QPTasks.h:459
void gains(double stiffness, double damping)
void dimWeight(const Eigen::VectorXd &dimW) noexcept
Definition: QPTasks.h:463
void stiffness(double stiffness)
const std::vector< std::vector< double > > posture() const
Definition: QPTasks.h:425
void jointsGains(const std::vector< rbd::MultiBody > &mbs, const std::vector< JointGains > &jgv)
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
virtual const Eigen::MatrixXd & Q() const override
void refVel(const Eigen::VectorXd &refVel) noexcept
Definition: QPTasks.h:452
double stiffness() const
Definition: QPTasks.h:427
tasks::PostureTask & task()
Definition: QPTasks.h:421
virtual const Eigen::VectorXd & C() const override
const Eigen::VectorXd & dimWeight() const noexcept
Definition: QPTasks.h:461
void gains(double stiffness)
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
void posture(std::vector< std::vector< double >> q)
Definition: QPTasks.h:423
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:440
void refAccel(const Eigen::VectorXd &refAccel) noexcept
Definition: QPTasks.h:454
const Eigen::VectorXd & eval() const
void jointsStiffness(const std::vector< rbd::MultiBody > &mbs, const std::vector< JointStiffness > &jsv)
double damping() const
Definition: QPTasks.h:429
const Eigen::VectorXd & refVel() const noexcept
Definition: QPTasks.h:453
Definition: QPTasks.h:1056
virtual int dim() override
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
void envPoint(const rbd::MultiBody &mb, const std::string &bName, const Eigen::Vector3d &point)
Definition: QPTasks.h:1073
virtual const Eigen::VectorXd & speed() const override
tasks::RelativeDistTask & task()
Definition: QPTasks.h:1066
virtual const Eigen::VectorXd & eval() const override
void vector(const rbd::MultiBody &mb, const std::string &bName, const Eigen::Vector3d &u)
Definition: QPTasks.h:1078
virtual const Eigen::MatrixXd & jac() const override
void robotPoint(const rbd::MultiBody &mb, const std::string &bName, const Eigen::Vector3d &point)
Definition: QPTasks.h:1068
virtual const Eigen::VectorXd & normalAcc() const override
RelativeDistTask(const std::vector< rbd::MultiBody > &mbs, const int rIndex, const double timestep, tasks::RelativeDistTask::rbInfo &rbi1, tasks::RelativeDistTask::rbInfo &rbi2, const Eigen::Vector3d &u1=Eigen::Vector3d::Zero(), const Eigen::Vector3d &u2=Eigen::Vector3d::Zero())
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:44
const Eigen::VectorXd & dimWeight() const
Definition: QPTasks.h:48
Eigen::VectorXd error_
Definition: QPTasks.h:60
void dimWeight(const Eigen::VectorXd &dim)
virtual const Eigen::MatrixXd & Q() const override
virtual const Eigen::VectorXd & C() const override
HighLevelTask * hlTask_
Definition: QPTasks.h:59
SetPointTaskCommon(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double weight)
SetPointTaskCommon(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, const Eigen::VectorXd &dimWeight, double weight)
void computeQC(Eigen::VectorXd &error)
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
SetPointTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double stiffness, double weight)
void stiffness(double stiffness)
double stiffness() const
Definition: QPTasks.h:89
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
SetPointTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double stiffness, const Eigen::VectorXd &dimWeight, double weight)
Definition: QPSolverData.h:28
Definition: QPTasks.h:634
virtual const Eigen::VectorXd & eval() const override
virtual const Eigen::VectorXd & speed() const override
const Eigen::Matrix3d & orientation() const
Definition: QPTasks.h:653
virtual int dim() override
SurfaceOrientationTask(const std::vector< rbd::MultiBody > &mbs, int robodIndex, const std::string &bodyName, const Eigen::Matrix3d &ori, const sva::PTransformd &X_b_s)
virtual const Eigen::VectorXd & normalAcc() const override
void orientation(const Eigen::Quaterniond &ori)
Definition: QPTasks.h:649
SurfaceOrientationTask(const std::vector< rbd::MultiBody > &mbs, int robodIndex, const std::string &bodyName, const Eigen::Quaterniond &ori, const sva::PTransformd &X_b_s)
tasks::SurfaceOrientationTask & task()
Definition: QPTasks.h:647
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
void orientation(const Eigen::Matrix3d &ori)
Definition: QPTasks.h:651
virtual const Eigen::MatrixXd & jac() const override
Definition: QPTasks.h:217
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
void iter(int i)
Definition: QPTasks.h:240
int nrIter() const
Definition: QPTasks.h:242
int iter() const
Definition: QPTasks.h:239
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
TargetObjectiveTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double timeStep, double duration, const Eigen::VectorXd &objDot, double weight)
virtual const Eigen::VectorXd & C() const override
TargetObjectiveTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double timeStep, double duration, const Eigen::VectorXd &objDot, const Eigen::VectorXd &dimWeight, double weight)
const Eigen::VectorXd & psi() const
Definition: QPTasks.h:252
void dimWeight(const Eigen::VectorXd &o)
Definition: QPTasks.h:249
virtual const Eigen::MatrixXd & Q() const override
void objDot(const Eigen::VectorXd &o)
Definition: QPTasks.h:246
const Eigen::VectorXd & dimWeight() const
Definition: QPTasks.h:248
void nrIter(int i)
Definition: QPTasks.h:243
const Eigen::VectorXd & objDot() const
Definition: QPTasks.h:245
const Eigen::VectorXd & phi() const
Definition: QPTasks.h:251
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:254
Definition: QPSolver.h:279
Definition: QPTasks.h:351
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
TorqueTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const TorqueBound &tb, const Eigen::VectorXd &jointSelect, double weight)
TorqueTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const TorqueBound &tb, double weight)
virtual const Eigen::VectorXd & jointSelect() const
Definition: QPTasks.h:401
TorqueTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const TorqueBound &tb, const TorqueDBound &tdb, double dt, const Eigen::VectorXd &jointSelect, double weight)
TorqueTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const TorqueBound &tb, const TorqueDBound &tdb, double dt, const std::string &efName, double weight)
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:395
virtual const Eigen::MatrixXd & Q() const override
Definition: QPTasks.h:397
TorqueTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const TorqueBound &tb, const std::string &efName, double weight)
TorqueTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const TorqueBound &tb, const TorqueDBound &tdb, double dt, double weight)
virtual const Eigen::VectorXd & C() const override
Definition: QPTasks.h:399
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
Definition: QPTasks.h:102
void refAccel(const Eigen::VectorXd &refAccel)
void errorPos(const Eigen::VectorXd &errorPos)
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
void errorVel(const Eigen::VectorXd &errorVel)
TrackingTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double gainPos, double gainVel, const Eigen::VectorXd &dimWeight, double weight)
void setGains(double gainPos, double gainVel)
TrackingTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double gainPos, double gainVel, double weight)
Definition: QPTasks.h:135
const Eigen::VectorXd & damping() const
void damping(const Eigen::VectorXd &damping)
void stiffness(const Eigen::VectorXd &stiffness)
void stiffness(double gainPos)
const Eigen::VectorXd & refAccel() const
void setGains(const Eigen::VectorXd &stiffness, const Eigen::VectorXd &damping)
const Eigen::VectorXd & stiffness() const
TrajectoryTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double gainPos, double gainVel, double weight)
void setGains(double gainPos, double gainVel)
void damping(double gainVel)
void refAccel(const Eigen::VectorXd &refAccel)
TrajectoryTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double gainPos, double gainVel, const Eigen::VectorXd &dimWeight, double weight)
void refVel(const Eigen::VectorXd &refVel)
void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
const Eigen::VectorXd & refVel() const
Definition: QPTasks.h:1100
void bodyVector(const Eigen::Vector3d &vector)
Definition: QPTasks.h:1109
virtual const Eigen::VectorXd & eval() const override
const Eigen::Vector3d & target() const
Definition: QPTasks.h:1112
void target(const Eigen::Vector3d &vector)
Definition: QPTasks.h:1111
virtual const Eigen::VectorXd & normalAcc() const override
const Eigen::Vector3d & actual() const
Definition: QPTasks.h:1113
VectorOrientationTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const Eigen::Vector3d &bodyVector, const Eigen::Vector3d &targetVector)
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
virtual int dim() override
tasks::VectorOrientationTask & task()
Definition: QPTasks.h:1108
const Eigen::Vector3d & bodyVector() const
Definition: QPTasks.h:1110
virtual const Eigen::VectorXd & speed() const override
virtual const Eigen::MatrixXd & jac() const override
Definition: GenQPSolver.h:21
Definition: GenQPUtils.h:19
Definition: QPTasks.h:337
std::string jointName
Definition: QPTasks.h:346
JointGains(const std::string &jName, double stif)
Definition: QPTasks.h:339
double damping
Definition: QPTasks.h:347
JointGains(const std::string &jName, double stif, double damp)
Definition: QPTasks.h:344
double stiffness
Definition: QPTasks.h:347
JointGains()
Definition: QPTasks.h:338
Definition: QPTasks.h:328
JointStiffness(const std::string &jName, double stif)
Definition: QPTasks.h:330
JointStiffness()
Definition: QPTasks.h:329
std::string jointName
Definition: QPTasks.h:332
double stiffness
Definition: QPTasks.h:333
Definition: QPTasks.h:298
int dof
Definition: QPTasks.h:299