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