QPTasks.h
Go to the documentation of this file.
1 /*
2  * Copyright 2012-2022 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
7 // includes
8 #include <cassert>
9 // std
10 #include <array>
11 
12 // Eigen
13 #include <Eigen/Core>
14 
15 // Tasks
16 #include "QPMotionConstr.h"
17 #include "QPSolver.h"
18 #include "Tasks.h"
19 
20 // forward declaration
21 // RBDyn
22 namespace rbd
23 {
24 class MultiBody;
25 struct MultiBodyConfig;
26 } // namespace rbd
27 
28 namespace tasks
29 {
30 
31 namespace qp
32 {
33 
34 class TASKS_DLLAPI SetPointTaskCommon : public Task
35 {
36 public:
37  SetPointTaskCommon(const std::vector<rbd::MultiBody> & mbs, int robotIndex, HighLevelTask * hlTask, double weight);
38  SetPointTaskCommon(const std::vector<rbd::MultiBody> & mbs,
39  int robotIndex,
40  HighLevelTask * hlTask,
41  const Eigen::VectorXd & dimWeight,
42  double weight);
43 
44  virtual std::pair<int, int> begin() const override { return std::make_pair(alphaDBegin_, alphaDBegin_); }
45 
46  void dimWeight(const Eigen::VectorXd & dim);
47 
48  const Eigen::VectorXd & dimWeight() const { return dimWeight_; }
49 
50  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
51 
52  virtual const Eigen::MatrixXd & Q() const override;
53  virtual const Eigen::VectorXd & C() const override;
54 
55 protected:
56  void computeQC(Eigen::VectorXd & error);
57 
58 protected:
60  Eigen::VectorXd error_;
61 
62 private:
63  Eigen::VectorXd dimWeight_;
64  int robotIndex_, alphaDBegin_;
65 
66  Eigen::MatrixXd Q_;
67  Eigen::VectorXd C_;
68  // cache
69  Eigen::MatrixXd preQ_;
70  Eigen::VectorXd preC_;
71 };
72 
73 class TASKS_DLLAPI SetPointTask : public SetPointTaskCommon
74 {
75 public:
76  SetPointTask(const std::vector<rbd::MultiBody> & mbs,
77  int robotIndex,
78  HighLevelTask * hlTask,
79  double stiffness,
80  double weight);
81 
82  SetPointTask(const std::vector<rbd::MultiBody> & mbs,
83  int robotIndex,
84  HighLevelTask * hlTask,
85  double stiffness,
86  const Eigen::VectorXd & dimWeight,
87  double weight);
88 
89  double stiffness() const { return stiffness_; }
90 
91  void stiffness(double stiffness);
92 
93  virtual void update(const std::vector<rbd::MultiBody> & mbs,
94  const std::vector<rbd::MultiBodyConfig> & mbcs,
95  const SolverData & data) override;
96 
97 private:
98  double stiffness_, stiffnessSqrt_;
99 };
100 
101 class TASKS_DLLAPI TrackingTask : public SetPointTaskCommon
102 {
103 public:
104  TrackingTask(const std::vector<rbd::MultiBody> & mbs,
105  int robotIndex,
106  HighLevelTask * hlTask,
107  double gainPos,
108  double gainVel,
109  double weight);
110 
111  TrackingTask(const std::vector<rbd::MultiBody> & mbs,
112  int robotIndex,
113  HighLevelTask * hlTask,
114  double gainPos,
115  double gainVel,
116  const Eigen::VectorXd & dimWeight,
117  double weight);
118 
119  void setGains(double gainPos, double gainVel);
120 
121  void errorPos(const Eigen::VectorXd & errorPos);
122  void errorVel(const Eigen::VectorXd & errorVel);
123  void refAccel(const Eigen::VectorXd & refAccel);
124 
125  virtual void update(const std::vector<rbd::MultiBody> & mbs,
126  const std::vector<rbd::MultiBodyConfig> & mbcs,
127  const SolverData & data) override;
128 
129 private:
130  double gainPos_, gainVel_;
131  Eigen::VectorXd errorPos_, errorVel_, refAccel_;
132 };
133 
134 class TASKS_DLLAPI TrajectoryTask : public SetPointTaskCommon
135 {
136 public:
137  TrajectoryTask(const std::vector<rbd::MultiBody> & mbs,
138  int robotIndex,
139  HighLevelTask * hlTask,
140  double gainPos,
141  double gainVel,
142  double weight);
143 
144  TrajectoryTask(const std::vector<rbd::MultiBody> & mbs,
145  int robotIndex,
146  HighLevelTask * hlTask,
147  double gainPos,
148  double gainVel,
149  const Eigen::VectorXd & dimWeight,
150  double weight);
151 
152  void setGains(double gainPos, double gainVel);
153  void setGains(const Eigen::VectorXd & stiffness, const Eigen::VectorXd & damping);
154  void stiffness(double gainPos);
155  void stiffness(const Eigen::VectorXd & stiffness);
156  const Eigen::VectorXd & stiffness() const;
157  void damping(double gainVel);
158  void damping(const Eigen::VectorXd & damping);
159  const Eigen::VectorXd & damping() const;
160 
161  void refVel(const Eigen::VectorXd & refVel);
162  const Eigen::VectorXd & refVel() const;
163  void refAccel(const Eigen::VectorXd & refAccel);
164  const Eigen::VectorXd & refAccel() const;
165 
166  void update(const std::vector<rbd::MultiBody> & mbs,
167  const std::vector<rbd::MultiBodyConfig> & mbcs,
168  const SolverData & data) override;
169 
170 private:
171  Eigen::VectorXd stiffness_, damping_;
172  Eigen::VectorXd refVel_, refAccel_;
173 };
174 
176 class TASKS_DLLAPI PIDTask : public SetPointTaskCommon
177 {
178 public:
179  PIDTask(const std::vector<rbd::MultiBody> & mbs,
180  int robotIndex,
181  HighLevelTask * hlTask,
182  double P,
183  double I,
184  double D,
185  double weight);
186 
187  PIDTask(const std::vector<rbd::MultiBody> & mbs,
188  int robotIndex,
189  HighLevelTask * hlTask,
190  double P,
191  double I,
192  double D,
193  const Eigen::VectorXd & dimWeight,
194  double weight);
195 
196  double P() const;
197  void P(double p);
198  double I() const;
199  void I(double i);
200  double D() const;
201  void D(double d);
202 
203  void error(const Eigen::VectorXd & err);
204  void errorD(const Eigen::VectorXd & errD);
205  void errorI(const Eigen::VectorXd & errI);
206 
207  virtual void update(const std::vector<rbd::MultiBody> & mbs,
208  const std::vector<rbd::MultiBodyConfig> & mbcs,
209  const SolverData & data) override;
210 
211 private:
212  double P_, I_, D_;
213  Eigen::VectorXd error_, errorD_, errorI_;
214 };
215 
216 class TASKS_DLLAPI TargetObjectiveTask : public Task
217 {
218 public:
219  TargetObjectiveTask(const std::vector<rbd::MultiBody> & mbs,
220  int robotIndex,
221  HighLevelTask * hlTask,
222  double timeStep,
223  double duration,
224  const Eigen::VectorXd & objDot,
225  double weight);
226 
227  TargetObjectiveTask(const std::vector<rbd::MultiBody> & mbs,
228  int robotIndex,
229  HighLevelTask * hlTask,
230  double timeStep,
231  double duration,
232  const Eigen::VectorXd & objDot,
233  const Eigen::VectorXd & dimWeight,
234  double weight);
235 
236  double duration() const;
237  void duration(double d);
238 
239  int iter() const { return iter_; }
240  void iter(int i) { iter_ = i; }
241 
242  int nrIter() const { return nrIter_; }
243  void nrIter(int i) { nrIter_ = i; }
244 
245  const Eigen::VectorXd & objDot() const { return objDot_; }
246  void objDot(const Eigen::VectorXd & o) { objDot_ = o; }
247 
248  const Eigen::VectorXd & dimWeight() const { return dimWeight_; }
249  void dimWeight(const Eigen::VectorXd & o) { dimWeight_ = o; }
250 
251  const Eigen::VectorXd & phi() const { return phi_; }
252  const Eigen::VectorXd & psi() const { return psi_; }
253 
254  virtual std::pair<int, int> begin() const override { return std::make_pair(alphaDBegin_, alphaDBegin_); }
255 
256  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
257  virtual void update(const std::vector<rbd::MultiBody> & mbs,
258  const std::vector<rbd::MultiBodyConfig> & mbcs,
259  const SolverData & data) override;
260 
261  virtual const Eigen::MatrixXd & Q() const override;
262  virtual const Eigen::VectorXd & C() const override;
263 
264 private:
265  HighLevelTask * hlTask_;
266 
267  int iter_, nrIter_;
268  double dt_;
269  Eigen::VectorXd objDot_;
270  Eigen::VectorXd dimWeight_;
271  int robotIndex_, alphaDBegin_;
272 
273  Eigen::VectorXd phi_, psi_;
274 
275  Eigen::MatrixXd Q_;
276  Eigen::VectorXd C_;
277  // cache
278  Eigen::MatrixXd preQ_;
279  Eigen::VectorXd CVecSum_, preC_;
280 };
281 
282 class TASKS_DLLAPI JointsSelector : public HighLevelTask
283 {
284 public:
285  static JointsSelector ActiveJoints(const std::vector<rbd::MultiBody> & mbs,
286  int robotIndex,
287  HighLevelTask * hl,
288  const std::vector<std::string> & activeJointsName,
289  const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {});
290  static JointsSelector UnactiveJoints(const std::vector<rbd::MultiBody> & mbs,
291  int robotIndex,
292  HighLevelTask * hl,
293  const std::vector<std::string> & unactiveJointsName,
294  const std::map<std::string, std::vector<std::array<int, 2>>> & unactiveDofs = {});
295 
296 public:
298  {
299  int posInDof, dof;
300  };
301 
302 public:
303  JointsSelector(const std::vector<rbd::MultiBody> & mbs,
304  int robotIndex,
305  HighLevelTask * hl,
306  const std::vector<std::string> & selectedJointsName,
307  const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {});
308 
309  const std::vector<SelectedData> selectedJoints() const { return selectedJoints_; }
310 
311  virtual int dim() override;
312  virtual void update(const std::vector<rbd::MultiBody> & mbs,
313  const std::vector<rbd::MultiBodyConfig> & mbcs,
314  const SolverData & data) override;
315 
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;
320 
321 private:
322  Eigen::MatrixXd jac_;
323  std::vector<SelectedData> selectedJoints_;
324  HighLevelTask * hl_;
325 };
326 
328 {
330  JointStiffness(const std::string & jName, double stif) : jointName(jName), stiffness(stif) {}
331 
332  std::string jointName;
333  double stiffness;
334 };
335 
337 {
339  JointGains(const std::string & jName, double stif) : jointName(jName), stiffness(stif)
340  {
341  damping = 2. * std::sqrt(stif);
342  }
343 
344  JointGains(const std::string & jName, double stif, double damp) : jointName(jName), stiffness(stif), damping(damp) {}
345 
346  std::string jointName;
348 };
349 
350 class TASKS_DLLAPI TorqueTask : public Task
351 {
352 public:
353  TorqueTask(const std::vector<rbd::MultiBody> & mbs, int robotIndex, const TorqueBound & tb, double weight);
354 
355  TorqueTask(const std::vector<rbd::MultiBody> & mbs,
356  int robotIndex,
357  const TorqueBound & tb,
358  const Eigen::VectorXd & jointSelect,
359  double weight);
360 
361  TorqueTask(const std::vector<rbd::MultiBody> & mbs,
362  int robotIndex,
363  const TorqueBound & tb,
364  const std::string & efName,
365  double weight);
366 
367  TorqueTask(const std::vector<rbd::MultiBody> & mbs,
368  int robotIndex,
369  const TorqueBound & tb,
370  const TorqueDBound & tdb,
371  double dt,
372  double weight);
373 
374  TorqueTask(const std::vector<rbd::MultiBody> & mbs,
375  int robotIndex,
376  const TorqueBound & tb,
377  const TorqueDBound & tdb,
378  double dt,
379  const Eigen::VectorXd & jointSelect,
380  double weight);
381 
382  TorqueTask(const std::vector<rbd::MultiBody> & mbs,
383  int robotIndex,
384  const TorqueBound & tb,
385  const TorqueDBound & tdb,
386  double dt,
387  const std::string & efName,
388  double weight);
389 
390  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
391  virtual void update(const std::vector<rbd::MultiBody> & mbs,
392  const std::vector<rbd::MultiBodyConfig> & mbcs,
393  const SolverData & data) override;
394 
395  virtual std::pair<int, int> begin() const override { return std::make_pair(0, 0); }
396 
397  virtual const Eigen::MatrixXd & Q() const override { return Q_; }
398 
399  virtual const Eigen::VectorXd & C() const override { return C_; }
400 
401  virtual const Eigen::VectorXd & jointSelect() const { return jointSelector_; }
402 
403 private:
404  int robotIndex_;
405  int alphaDBegin_, lambdaBegin_;
406  MotionConstr motionConstr;
407  Eigen::VectorXd jointSelector_;
408  Eigen::MatrixXd Q_;
409  Eigen::VectorXd C_;
410 };
411 
412 class TASKS_DLLAPI PostureTask : public Task
413 {
414 public:
415  PostureTask(const std::vector<rbd::MultiBody> & mbs,
416  int robotIndex,
417  std::vector<std::vector<double>> q,
418  double stiffness,
419  double weight);
420 
421  tasks::PostureTask & task() { return pt_; }
422 
423  void posture(std::vector<std::vector<double>> q) { pt_.posture(q); }
424 
425  const std::vector<std::vector<double>> posture() const { return pt_.posture(); }
426 
427  double stiffness() const { return stiffness_; }
428 
429  double damping() const { return damping_; }
430 
431  void stiffness(double stiffness);
432 
433  void gains(double stiffness);
434  void gains(double stiffness, double damping);
435 
436  void jointsStiffness(const std::vector<rbd::MultiBody> & mbs, const std::vector<JointStiffness> & jsv);
437 
438  void jointsGains(const std::vector<rbd::MultiBody> & mbs, const std::vector<JointGains> & jgv);
439 
440  virtual std::pair<int, int> begin() const override { return std::make_pair(alphaDBegin_, alphaDBegin_); }
441 
442  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
443  virtual void update(const std::vector<rbd::MultiBody> & mbs,
444  const std::vector<rbd::MultiBodyConfig> & mbcs,
445  const SolverData & data) override;
446 
447  virtual const Eigen::MatrixXd & Q() const override;
448  virtual const Eigen::VectorXd & C() const override;
449 
450  const Eigen::VectorXd & eval() const;
451 
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
455  {
456  assert(refAccel.size() == refAccel_.size());
457  refAccel_ = refAccel;
458  }
459  inline const Eigen::VectorXd & refAccel() const noexcept { return refAccel_; }
460 
461  inline const Eigen::VectorXd & dimWeight() const noexcept { return dimWeight_; }
462 
463  inline void dimWeight(const Eigen::VectorXd & dimW) noexcept
464  {
465  assert(dimW.size() == dimWeight_.size());
466  dimWeight_ = dimW;
467  }
468 
469 private:
470  struct JointData
471  {
472  double stiffness, damping;
473  int start, size;
474  };
475 
476 private:
477  tasks::PostureTask pt_;
478 
479  double stiffness_;
480  double damping_;
481  int robotIndex_, alphaDBegin_;
482 
483  std::vector<JointData> jointDatas_;
484 
485  Eigen::MatrixXd Q_;
486  Eigen::VectorXd C_;
487  Eigen::VectorXd alphaVec_;
488  Eigen::VectorXd refVel_, refAccel_;
489  Eigen::VectorXd dimWeight_;
490 };
491 
492 class TASKS_DLLAPI PositionTask : public HighLevelTask
493 {
494 public:
495  PositionTask(const std::vector<rbd::MultiBody> & mbs,
496  int robotIndex,
497  const std::string & bodyName,
498  const Eigen::Vector3d & pos,
499  const Eigen::Vector3d & bodyPoint = Eigen::Vector3d::Zero());
500 
501  tasks::PositionTask & task() { return pt_; }
502 
503  void position(const Eigen::Vector3d & pos) { pt_.position(pos); }
504 
505  const Eigen::Vector3d & position() const { return pt_.position(); }
506 
507  void bodyPoint(const Eigen::Vector3d & point) { pt_.bodyPoint(point); }
508 
509  const Eigen::Vector3d & bodyPoint() const { return pt_.bodyPoint(); }
510 
511  virtual int dim() override;
512  virtual void update(const std::vector<rbd::MultiBody> & mb,
513  const std::vector<rbd::MultiBodyConfig> & mbc,
514  const SolverData & data) override;
515 
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;
520 
521 private:
523  int robotIndex_;
524 };
525 
526 class TASKS_DLLAPI OrientationTask : public HighLevelTask
527 {
528 public:
529  OrientationTask(const std::vector<rbd::MultiBody> & mbs,
530  int robodIndex,
531  const std::string & bodyName,
532  const Eigen::Quaterniond & ori);
533  OrientationTask(const std::vector<rbd::MultiBody> & mbs,
534  int robodIndex,
535  const std::string & bodyName,
536  const Eigen::Matrix3d & ori);
537 
538  tasks::OrientationTask & task() { return ot_; }
539 
540  void orientation(const Eigen::Quaterniond & ori) { ot_.orientation(ori); }
541 
542  void orientation(const Eigen::Matrix3d & ori) { ot_.orientation(ori); }
543 
544  const Eigen::Matrix3d & orientation() const { return ot_.orientation(); }
545 
546  virtual int dim() override;
547  virtual void update(const std::vector<rbd::MultiBody> & mbs,
548  const std::vector<rbd::MultiBodyConfig> & mbcs,
549  const SolverData & data) override;
550 
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;
555 
556 private:
558  int robotIndex_;
559 };
560 
561 template<typename transform_task_t>
563 {
564 public:
565  TransformTaskCommon(const std::vector<rbd::MultiBody> & mbs,
566  int robotIndex,
567  const std::string & bodyName,
568  const sva::PTransformd & X_0_t,
569  const sva::PTransformd & X_b_p = sva::PTransformd::Identity())
570  : tt_(mbs[robotIndex], bodyName, X_0_t, X_b_p), robotIndex_(robotIndex)
571  {
572  }
573 
574  transform_task_t & task() { return tt_; }
575 
576  void target(const sva::PTransformd & X_0_t) { tt_.target(X_0_t); }
577 
578  const sva::PTransformd & target() const { return tt_.target(); }
579 
580  void X_b_p(const sva::PTransformd & X_b_p) { tt_.X_b_p(X_b_p); }
581 
582  const sva::PTransformd & X_b_p() const { return tt_.X_b_p(); }
583 
584  virtual int dim() override { return 6; }
585 
586  virtual const Eigen::MatrixXd & jac() const override { return tt_.jac(); }
587 
588  virtual const Eigen::VectorXd & eval() const override { return tt_.eval(); }
589 
590  virtual const Eigen::VectorXd & speed() const override { return tt_.speed(); }
591 
592  virtual const Eigen::VectorXd & normalAcc() const override { return tt_.normalAcc(); }
593 
594 protected:
595  transform_task_t tt_;
597 };
598 
600 class TASKS_DLLAPI SurfaceTransformTask : public TransformTaskCommon<tasks::SurfaceTransformTask>
601 {
602 public:
603  SurfaceTransformTask(const std::vector<rbd::MultiBody> & mbs,
604  int robotIndex,
605  const std::string & bodyName,
606  const sva::PTransformd & X_0_t,
607  const sva::PTransformd & X_b_p = sva::PTransformd::Identity());
608 
609  virtual void update(const std::vector<rbd::MultiBody> & mb,
610  const std::vector<rbd::MultiBodyConfig> & mbc,
611  const SolverData & data) override;
612 };
613 
615 class TASKS_DLLAPI TransformTask : public TransformTaskCommon<tasks::TransformTask>
616 {
617 public:
618  TransformTask(const std::vector<rbd::MultiBody> & mbs,
619  int robotIndex,
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());
624 
625  void E_0_c(const Eigen::Matrix3d & E_0_c);
626  const Eigen::Matrix3d & E_0_c() const;
627 
628  virtual void update(const std::vector<rbd::MultiBody> & mb,
629  const std::vector<rbd::MultiBodyConfig> & mbc,
630  const SolverData & data) override;
631 };
632 
633 class TASKS_DLLAPI SurfaceOrientationTask : public HighLevelTask
634 {
635 public:
636  SurfaceOrientationTask(const std::vector<rbd::MultiBody> & mbs,
637  int robodIndex,
638  const std::string & bodyName,
639  const Eigen::Quaterniond & ori,
640  const sva::PTransformd & X_b_s);
641  SurfaceOrientationTask(const std::vector<rbd::MultiBody> & mbs,
642  int robodIndex,
643  const std::string & bodyName,
644  const Eigen::Matrix3d & ori,
645  const sva::PTransformd & X_b_s);
646 
648 
649  void orientation(const Eigen::Quaterniond & ori) { ot_.orientation(ori); }
650 
651  void orientation(const Eigen::Matrix3d & ori) { ot_.orientation(ori); }
652 
653  const Eigen::Matrix3d & orientation() const { return ot_.orientation(); }
654 
655  virtual int dim() override;
656  virtual void update(const std::vector<rbd::MultiBody> & mbs,
657  const std::vector<rbd::MultiBodyConfig> & mbcs,
658  const SolverData & data) override;
659 
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;
664 
665 private:
667  int robotIndex_;
668 };
669 
670 class TASKS_DLLAPI GazeTask : public HighLevelTask
671 {
672 public:
673  GazeTask(const std::vector<rbd::MultiBody> & mbs,
674  int robotIndex,
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());
680  GazeTask(const std::vector<rbd::MultiBody> & mbs,
681  int robotIndex,
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());
686 
687  tasks::GazeTask & task() { return gazet_; }
688 
689  void error(const Eigen::Vector2d & point2d, const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero())
690  {
691  gazet_.error(point2d, point2d_ref);
692  }
693 
694  void error(const Eigen::Vector3d & point3d, const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero())
695  {
696  gazet_.error(point3d, point2d_ref);
697  }
698 
699  virtual int dim() override;
700  virtual void update(const std::vector<rbd::MultiBody> & mbs,
701  const std::vector<rbd::MultiBodyConfig> & mbcs,
702  const SolverData & data) override;
703 
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;
708 
709 private:
710  tasks::GazeTask gazet_;
711  int robotIndex_;
712 };
713 
714 class TASKS_DLLAPI PositionBasedVisServoTask : public HighLevelTask
715 {
716 public:
717  PositionBasedVisServoTask(const std::vector<rbd::MultiBody> & mbs,
718  int robotIndex,
719  const std::string & bodyName,
720  const sva::PTransformd & X_t_s,
721  const sva::PTransformd & X_b_s = sva::PTransformd::Identity());
722 
723  tasks::PositionBasedVisServoTask & task() { return pbvst_; }
724 
725  void error(const sva::PTransformd & X_t_s) { pbvst_.error(X_t_s); }
726 
727  virtual int dim() override;
728  virtual void update(const std::vector<rbd::MultiBody> & mbs,
729  const std::vector<rbd::MultiBodyConfig> & mbcs,
730  const SolverData & data) override;
731 
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;
736 
737 private:
739  int robotIndex_;
740 };
741 
742 class TASKS_DLLAPI CoMTask : public HighLevelTask
743 {
744 public:
745  CoMTask(const std::vector<rbd::MultiBody> & mbs, int robotIndex, const Eigen::Vector3d & com);
746  CoMTask(const std::vector<rbd::MultiBody> & mbs,
747  int robotIndex,
748  const Eigen::Vector3d & com,
749  std::vector<double> weight);
750 
751  tasks::CoMTask & task() { return ct_; }
752 
753  void com(const Eigen::Vector3d & com) { ct_.com(com); }
754 
755  const Eigen::Vector3d & com() const { return ct_.com(); }
756 
757  const Eigen::Vector3d & actual() const { return ct_.actual(); }
758 
759  void updateInertialParameters(const std::vector<rbd::MultiBody> & mbs);
760 
761  virtual int dim() override;
762  virtual void update(const std::vector<rbd::MultiBody> & mbs,
763  const std::vector<rbd::MultiBodyConfig> & mbcs,
764  const SolverData & data) override;
765 
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;
770 
771 private:
772  tasks::CoMTask ct_;
773  int robotIndex_;
774 };
775 
776 class TASKS_DLLAPI MultiCoMTask : public Task
777 {
778 public:
779  MultiCoMTask(const std::vector<rbd::MultiBody> & mb,
780  std::vector<int> robotIndexes,
781  const Eigen::Vector3d & com,
782  double stiffness,
783  double weight);
784  MultiCoMTask(const std::vector<rbd::MultiBody> & mb,
785  std::vector<int> robotIndexes,
786  const Eigen::Vector3d & com,
787  double stiffness,
788  const Eigen::Vector3d & dimWeight,
789  double weight);
790 
791  tasks::MultiCoMTask & task() { return mct_; }
792 
793  void com(const Eigen::Vector3d & com) { mct_.com(com); }
794 
795  const Eigen::Vector3d com() const { return mct_.com(); }
796 
797  void updateInertialParameters(const std::vector<rbd::MultiBody> & mbs);
798 
799  double stiffness() const { return stiffness_; }
800 
801  void stiffness(double stiffness);
802 
803  void dimWeight(const Eigen::Vector3d & dim);
804 
805  const Eigen::Vector3d & dimWeight() const { return dimWeight_; }
806 
807  virtual std::pair<int, int> begin() const override { return {alphaDBegin_, alphaDBegin_}; }
808 
809  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
810  virtual void update(const std::vector<rbd::MultiBody> & mbs,
811  const std::vector<rbd::MultiBodyConfig> & mbcs,
812  const SolverData & data) override;
813 
814  virtual const Eigen::MatrixXd & Q() const override;
815  virtual const Eigen::VectorXd & C() const override;
816 
817  const Eigen::VectorXd & eval() const;
818  const Eigen::VectorXd & speed() const;
819 
820 private:
821  void init(const std::vector<rbd::MultiBody> & mbs);
822 
823 private:
824  int alphaDBegin_;
825  double stiffness_, stiffnessSqrt_;
826  Eigen::Vector3d dimWeight_;
827  std::vector<int> posInQ_;
828  tasks::MultiCoMTask mct_;
829  Eigen::MatrixXd Q_;
830  Eigen::VectorXd C_;
831  Eigen::Vector3d CSum_;
832  // cache
833  Eigen::MatrixXd preQ_;
834 };
835 
836 class TASKS_DLLAPI MultiRobotTransformTask : public Task
837 {
838 public:
839  MultiRobotTransformTask(const std::vector<rbd::MultiBody> & mbs,
840  int r1Index,
841  int r2Index,
842  const std::string & r1BodyName,
843  const std::string & r2BodyName,
844  const sva::PTransformd & X_r1b_r1s,
845  const sva::PTransformd & X_r2b_r2s,
846  double stiffness,
847  double weight);
848 
849  tasks::MultiRobotTransformTask & task() { return mrtt_; }
850 
851  void X_r1b_r1s(const sva::PTransformd & X_r1b_r1s);
852  const sva::PTransformd & X_r1b_r1s() const;
853 
854  void X_r2b_r2s(const sva::PTransformd & X_r2b_r2s);
855  const sva::PTransformd & X_r2b_r2s() const;
856 
857  double stiffness() const { return stiffness_; }
858 
859  void stiffness(double stiffness);
860 
861  void dimWeight(const Eigen::Vector6d & dim);
862 
863  const Eigen::VectorXd & dimWeight() const { return dimWeight_; }
864 
865  virtual std::pair<int, int> begin() const override { return {alphaDBegin_, alphaDBegin_}; }
866 
867  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
868  virtual void update(const std::vector<rbd::MultiBody> & mbs,
869  const std::vector<rbd::MultiBodyConfig> & mbcs,
870  const SolverData & data) override;
871 
872  virtual const Eigen::MatrixXd & Q() const override;
873  virtual const Eigen::VectorXd & C() const override;
874 
875  const Eigen::VectorXd & eval() const;
876  const Eigen::VectorXd & speed() const;
877 
878 private:
879  int alphaDBegin_;
880  double stiffness_, stiffnessSqrt_;
881  Eigen::VectorXd dimWeight_;
882  std::vector<int> posInQ_, robotIndexes_;
884  Eigen::MatrixXd Q_;
885  Eigen::VectorXd C_;
886  Eigen::VectorXd CSum_;
887  // cache
888  Eigen::MatrixXd preQ_;
889 };
890 
891 class TASKS_DLLAPI MomentumTask : public HighLevelTask
892 {
893 public:
894  MomentumTask(const std::vector<rbd::MultiBody> & mbs, int robotIndex, const sva::ForceVecd & mom);
895 
896  tasks::MomentumTask & task() { return momt_; }
897 
898  void momentum(const sva::ForceVecd & mom) { momt_.momentum(mom); }
899 
900  const sva::ForceVecd momentum() const { return momt_.momentum(); }
901 
902  virtual int dim() override;
903  virtual void update(const std::vector<rbd::MultiBody> & mb,
904  const std::vector<rbd::MultiBodyConfig> & mbc,
905  const SolverData & data) override;
906 
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;
911 
912 private:
913  tasks::MomentumTask momt_;
914  int robotIndex_;
915 };
916 
917 class TASKS_DLLAPI ContactTask : public Task
918 {
919 public:
920  ContactTask(ContactId contactId, double stiffness, double weight)
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_()
923  {
924  }
925 
926  virtual std::pair<int, int> begin() const override { return std::make_pair(begin_, begin_); }
927 
928  void error(const Eigen::Vector3d & error);
929  void errorD(const Eigen::Vector3d & errorD);
930 
931  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
932  virtual void update(const std::vector<rbd::MultiBody> & mbs,
933  const std::vector<rbd::MultiBodyConfig> & mbcs,
934  const SolverData & data) override;
935 
936  virtual const Eigen::MatrixXd & Q() const override;
937  virtual const Eigen::VectorXd & C() const override;
938 
939 private:
940  ContactId contactId_;
941  int begin_;
942 
943  double stiffness_, stiffnessSqrt_;
944  Eigen::MatrixXd conesJac_;
945  Eigen::Vector3d error_, errorD_;
946 
947  Eigen::MatrixXd Q_;
948  Eigen::VectorXd C_;
949 };
950 
951 class TASKS_DLLAPI GripperTorqueTask : public Task
952 {
953 public:
954  GripperTorqueTask(ContactId contactId, const Eigen::Vector3d & origin, const Eigen::Vector3d & axis, double weight)
955  : Task(weight), contactId_(contactId), origin_(origin), axis_(axis), begin_(0), Q_(), C_()
956  {
957  }
958 
959  virtual std::pair<int, int> begin() const override { return std::make_pair(begin_, begin_); }
960 
961  virtual void updateNrVars(const std::vector<rbd::MultiBody> & mbs, const SolverData & data) override;
962  virtual void update(const std::vector<rbd::MultiBody> & mbs,
963  const std::vector<rbd::MultiBodyConfig> & mbcs,
964  const SolverData & data) override;
965 
966  virtual const Eigen::MatrixXd & Q() const override;
967  virtual const Eigen::VectorXd & C() const override;
968 
969 private:
970  ContactId contactId_;
971  Eigen::Vector3d origin_;
972  Eigen::Vector3d axis_;
973  int begin_;
974 
975  Eigen::MatrixXd Q_;
976  Eigen::VectorXd C_;
977 };
978 
979 class TASKS_DLLAPI LinVelocityTask : public HighLevelTask
980 {
981 public:
982  LinVelocityTask(const std::vector<rbd::MultiBody> & mbs,
983  int robotIndex,
984  const std::string & bodyName,
985  const Eigen::Vector3d & vel,
986  const Eigen::Vector3d & bodyPoint = Eigen::Vector3d::Zero());
987 
988  tasks::LinVelocityTask & task() { return pt_; }
989 
990  void velocity(const Eigen::Vector3d & s) { pt_.velocity(s); }
991 
992  const Eigen::Vector3d & velocity() const { return pt_.velocity(); }
993 
994  void bodyPoint(const Eigen::Vector3d & point) { pt_.bodyPoint(point); }
995 
996  const Eigen::Vector3d & bodyPoint() const { return pt_.bodyPoint(); }
997 
998  virtual int dim() override;
999  virtual void update(const std::vector<rbd::MultiBody> & mbs,
1000  const std::vector<rbd::MultiBodyConfig> & mbcs,
1001  const SolverData & data) override;
1002 
1003  virtual const Eigen::MatrixXd & jac() const override;
1004  virtual const Eigen::VectorXd & eval() const override;
1005  virtual const Eigen::VectorXd & speed() const override;
1006  virtual const Eigen::VectorXd & normalAcc() const override;
1007 
1008 private:
1010  int robotIndex_;
1011 };
1012 
1013 class TASKS_DLLAPI OrientationTrackingTask : public HighLevelTask
1014 {
1015 public:
1016  OrientationTrackingTask(const std::vector<rbd::MultiBody> & mbs,
1017  int robotIndex,
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);
1023 
1025 
1026  void trackedPoint(const Eigen::Vector3d & tp) { ott_.trackedPoint(tp); }
1027 
1028  const Eigen::Vector3d & trackedPoint() const { return ott_.trackedPoint(); }
1029 
1030  void bodyPoint(const Eigen::Vector3d & bp) { ott_.bodyPoint(bp); }
1031 
1032  const Eigen::Vector3d & bodyPoint() const { return ott_.bodyPoint(); }
1033 
1034  void bodyAxis(const Eigen::Vector3d & ba) { ott_.bodyAxis(ba); }
1035 
1036  const Eigen::Vector3d & bodyAxis() const { return ott_.bodyAxis(); }
1037 
1038  virtual int dim() override;
1039  virtual void update(const std::vector<rbd::MultiBody> & mbs,
1040  const std::vector<rbd::MultiBodyConfig> & mbcs,
1041  const SolverData & data) override;
1042 
1043  virtual const Eigen::MatrixXd & jac() const override;
1044  virtual const Eigen::VectorXd & eval() const override;
1045  virtual const Eigen::VectorXd & speed() const override;
1046  virtual const Eigen::VectorXd & normalAcc() const override;
1047 
1048 private:
1049  int robotIndex_;
1051  Eigen::VectorXd alphaVec_;
1052  Eigen::VectorXd speed_, normalAcc_;
1053 };
1054 
1055 class TASKS_DLLAPI RelativeDistTask : public HighLevelTask
1056 {
1057 public:
1058  RelativeDistTask(const std::vector<rbd::MultiBody> & mbs,
1059  const int rIndex,
1060  const double timestep,
1063  const Eigen::Vector3d & u1 = Eigen::Vector3d::Zero(),
1064  const Eigen::Vector3d & u2 = Eigen::Vector3d::Zero());
1065 
1066  tasks::RelativeDistTask & task() { return rdt_; }
1067 
1068  void robotPoint(const rbd::MultiBody & mb, const std::string & bName, const Eigen::Vector3d & point)
1069  {
1070  int bIndex = mb.bodyIndexByName(bName);
1071  rdt_.robotPoint(bIndex, point);
1072  }
1073  void envPoint(const rbd::MultiBody & mb, const std::string & bName, const Eigen::Vector3d & point)
1074  {
1075  int bIndex = mb.bodyIndexByName(bName);
1076  rdt_.envPoint(bIndex, point);
1077  }
1078  void vector(const rbd::MultiBody & mb, const std::string & bName, const Eigen::Vector3d & u)
1079  {
1080  int bIndex = mb.bodyIndexByName(bName);
1081  rdt_.vector(bIndex, u);
1082  }
1083 
1084  virtual int dim() override;
1085  virtual void update(const std::vector<rbd::MultiBody> & mbs,
1086  const std::vector<rbd::MultiBodyConfig> & mbcs,
1087  const SolverData & data) override;
1088 
1089  virtual const Eigen::MatrixXd & jac() const override;
1090  virtual const Eigen::VectorXd & eval() const override;
1091  virtual const Eigen::VectorXd & speed() const override;
1092  virtual const Eigen::VectorXd & normalAcc() const override;
1093 
1094 private:
1095  int rIndex_;
1097 };
1098 
1099 class TASKS_DLLAPI VectorOrientationTask : public HighLevelTask
1100 {
1101 public:
1102  VectorOrientationTask(const std::vector<rbd::MultiBody> & mbs,
1103  int robotIndex,
1104  const std::string & bodyName,
1105  const Eigen::Vector3d & bodyVector,
1106  const Eigen::Vector3d & targetVector);
1107 
1108  tasks::VectorOrientationTask & task() { return vot_; }
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(); }
1114 
1115  virtual int dim() override;
1116  virtual void update(const std::vector<rbd::MultiBody> & mbs,
1117  const std::vector<rbd::MultiBodyConfig> & mbcs,
1118  const SolverData & data) override;
1119 
1120  virtual const Eigen::MatrixXd & jac() const override;
1121  virtual const Eigen::VectorXd & eval() const override;
1122  virtual const Eigen::VectorXd & speed() const override;
1123  virtual const Eigen::VectorXd & normalAcc() const override;
1124 
1125 private:
1127  int robotIndex_;
1128 };
1129 
1130 } // namespace qp
1131 
1132 } // namespace tasks
Definition: Tasks.h:397
Definition: Tasks.h:270
Definition: Tasks.h:513
Definition: Tasks.h:482
Definition: Tasks.h:435
Definition: Tasks.h:185
Definition: Tasks.h:73
Definition: Tasks.h:553
Definition: Tasks.h:326
Definition: Tasks.h:33
Definition: Tasks.h:374
Definition: Tasks.h:596
std::tuple< std::string, Eigen::Vector3d, Eigen::Vector3d > rbInfo
Definition: Tasks.h:599
Definition: Tasks.h:228
Definition: Tasks.h:650
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:918
ContactTask(ContactId contactId, double stiffness, double weight)
Definition: QPTasks.h:920
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
void errorD(const Eigen::Vector3d &errorD)
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
virtual const Eigen::VectorXd & C() const override
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:926
void error(const Eigen::Vector3d &error)
virtual const Eigen::MatrixXd & Q() 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:837
const sva::PTransformd & X_r1b_r1s() const
void dimWeight(const Eigen::Vector6d &dim)
void X_r1b_r1s(const sva::PTransformd &X_r1b_r1s)
MultiRobotTransformTask(const std::vector< rbd::MultiBody > &mbs, int r1Index, int r2Index, const std::string &r1BodyName, const std::string &r2BodyName, const sva::PTransformd &X_r1b_r1s, const sva::PTransformd &X_r2b_r2s, double stiffness, double weight)
virtual void updateNrVars(const std::vector< rbd::MultiBody > &mbs, const SolverData &data) override
virtual std::pair< int, int > begin() const override
Definition: QPTasks.h:865
virtual void update(const std::vector< rbd::MultiBody > &mbs, const std::vector< rbd::MultiBodyConfig > &mbcs, const SolverData &data) override
void X_r2b_r2s(const sva::PTransformd &X_r2b_r2s)
const Eigen::VectorXd & dimWeight() const
Definition: QPTasks.h:863
double stiffness() const
Definition: QPTasks.h:857
const Eigen::VectorXd & eval() const
void stiffness(double stiffness)
virtual const Eigen::VectorXd & C() const override
const Eigen::VectorXd & speed() const
virtual const Eigen::MatrixXd & Q() const override
tasks::MultiRobotTransformTask & task()
Definition: QPTasks.h:849
const sva::PTransformd & X_r2b_r2s() 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)
double I() const
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)
void P(double p)
double P() const
PIDTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, HighLevelTask *hlTask, double P, double I, double D, const Eigen::VectorXd &dimWeight, double weight)
void D(double d)
void I(double i)
void errorD(const Eigen::VectorXd &errD)
double D() const
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 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())
Definition: QPTasks.h:35
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
Definition: QPTasks.h:74
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
TransformTask in surface frame.
Definition: QPTasks.h:601
virtual void update(const std::vector< rbd::MultiBody > &mb, const std::vector< rbd::MultiBodyConfig > &mbc, const SolverData &data) override
SurfaceTransformTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const sva::PTransformd &X_0_t, const sva::PTransformd &X_b_p=sva::PTransformd::Identity())
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:563
const sva::PTransformd & target() const
Definition: QPTasks.h:578
transform_task_t & task()
Definition: QPTasks.h:574
virtual const Eigen::VectorXd & normalAcc() const override
Definition: QPTasks.h:592
transform_task_t tt_
Definition: QPTasks.h:595
virtual const Eigen::VectorXd & eval() const override
Definition: QPTasks.h:588
const sva::PTransformd & X_b_p() const
Definition: QPTasks.h:582
virtual const Eigen::VectorXd & speed() const override
Definition: QPTasks.h:590
int robotIndex_
Definition: QPTasks.h:596
void X_b_p(const sva::PTransformd &X_b_p)
Definition: QPTasks.h:580
virtual const Eigen::MatrixXd & jac() const override
Definition: QPTasks.h:586
virtual int dim() override
Definition: QPTasks.h:584
TransformTaskCommon(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const sva::PTransformd &X_0_t, const sva::PTransformd &X_b_p=sva::PTransformd::Identity())
Definition: QPTasks.h:565
void target(const sva::PTransformd &X_0_t)
Definition: QPTasks.h:576
TransformTask in world or user frame.
Definition: QPTasks.h:616
const Eigen::Matrix3d & E_0_c() const
virtual void update(const std::vector< rbd::MultiBody > &mb, const std::vector< rbd::MultiBodyConfig > &mbc, const SolverData &data) override
void E_0_c(const Eigen::Matrix3d &E_0_c)
TransformTask(const std::vector< rbd::MultiBody > &mbs, int robotIndex, const std::string &bodyName, const sva::PTransformd &X_0_t, const sva::PTransformd &X_b_p=sva::PTransformd::Identity(), const Eigen::Matrix3d &E_0_c=Eigen::Matrix3d::Identity())
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: Bounds.h:95
Definition: Bounds.h:113
Definition: QPContacts.h:50
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
int dof
Definition: QPTasks.h:299