operator.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2010,
3  * François Bleibel,
4  * Olivier Stasse,
5  * Nicolas Mansard
6  * Joseph Mirabel
7  *
8  * CNRS/AIST
9  *
10  */
11 
13 #include <dynamic-graph/factory.h>
15 
16 #include <boost/function.hpp>
17 #include <boost/numeric/conversion/cast.hpp>
18 #include <deque>
19 #include <sot/core/binary-op.hh>
20 #include <sot/core/debug.hh>
21 #include <sot/core/factory.hh>
23 #include <sot/core/unary-op.hh>
24 #include <sot/core/variadic-op.hh>
25 
26 #include "../tools/type-name-helper.hh"
27 
28 namespace dg = ::dynamicgraph;
29 
30 /* ---------------------------------------------------------------------------*/
31 /* ------- GENERIC HELPERS -------------------------------------------------- */
32 /* ---------------------------------------------------------------------------*/
33 
34 #define ADD_COMMAND(name, def) commandMap.insert(std::make_pair(name, def))
35 
36 namespace dynamicgraph {
37 namespace sot {
38 template <typename TypeIn, typename TypeOut>
39 struct UnaryOpHeader {
40  typedef TypeIn Tin;
41  typedef TypeOut Tout;
42  static inline std::string nameTypeIn(void) {
44  }
45  static inline std::string nameTypeOut(void) {
47  }
49  inline std::string getDocString() const {
50  return std::string(
51  "Undocumented unary operator\n"
52  " - input ") +
53  nameTypeIn() +
54  std::string(
55  "\n"
56  " - output ") +
57  nameTypeOut() + std::string("\n");
58  }
59 };
60 
61 /* ---------------------------------------------------------------------- */
62 /* --- ALGEBRA SELECTORS ------------------------------------------------ */
63 /* ---------------------------------------------------------------------- */
64 struct VectorSelecter : public UnaryOpHeader<dg::Vector, dg::Vector> {
65  inline void operator()(const Tin &m, Vector &res) const {
66  res.resize(size);
67  Vector::Index r = 0;
68  for (std::size_t i = 0; i < idxs.size(); ++i) {
69  const Vector::Index &R = idxs[i].first;
70  const Vector::Index &nr = idxs[i].second;
71  assert((nr >= 0) && (R + nr <= m.size()));
72  res.segment(r, nr) = m.segment(R, nr);
73  r += nr;
74  }
75  assert(r == size);
76  }
77 
78  typedef std::pair<Vector::Index, Vector::Index> segment_t;
79  typedef std::vector<segment_t> segments_t;
82 
83  inline void setBounds(const size_type &m, const size_type &M) {
84  idxs = segments_t(1, segment_t(m, M - m));
85  size = M - m;
86  }
87  inline void addBounds(const size_type &m, const size_type &M) {
88  idxs.push_back(segment_t(m, M - m));
89  size += M - m;
90  }
91 
92  inline void addSpecificCommands(Entity &ent,
93  Entity::CommandMap_t &commandMap) {
94  using namespace dynamicgraph::command;
95  std::string doc;
96 
97  boost::function<void(const size_type &, const size_type &)> setBound =
98  boost::bind(&VectorSelecter::setBounds, this, _1, _2);
99  doc = docCommandVoid2("Set the bound of the selection [m,M[.",
100  "size_type (min)", "size_type (max)");
101  ADD_COMMAND("selec", makeCommandVoid2(ent, setBound, doc));
102  boost::function<void(const size_type &, const size_type &)> addBound =
103  boost::bind(&VectorSelecter::addBounds, this, _1, _2);
104  doc = docCommandVoid2("Add a segment to be selected [m,M[.",
105  "size_type (min)", "size_type (max)");
106  ADD_COMMAND("addSelec", makeCommandVoid2(ent, addBound, doc));
107  }
109 };
110 
111 /* ---------------------------------------------------------------------- */
112 struct VectorComponent : public UnaryOpHeader<dg::Vector, double> {
113  inline void operator()(const Tin &m, double &res) const {
114  assert(index < m.size());
115  res = m(index);
116  }
117 
119  inline void setIndex(const size_type &m) { index = m; }
120 
121  inline void addSpecificCommands(Entity &ent,
122  Entity::CommandMap_t &commandMap) {
123  std::string doc;
124 
125  boost::function<void(const int &)> callback =
126  boost::bind(&VectorComponent::setIndex, this, _1);
127  doc = command::docCommandVoid1("Set the index of the component.",
128  "size_type (index)");
129  ADD_COMMAND("setIndex", command::makeCommandVoid1(ent, callback, doc));
130  }
131  inline std::string getDocString() const {
132  std::string docString(
133  "Select a component of a vector\n"
134  " - input vector\n"
135  " - output double");
136  return docString;
137  }
138 };
139 
140 /* ---------------------------------------------------------------------- */
141 struct MatrixSelector : public UnaryOpHeader<dg::Matrix, dg::Matrix> {
142  inline void operator()(const Matrix &m, Matrix &res) const {
143  assert((imin <= imax) && (imax <= m.rows()));
144  assert((jmin <= jmax) && (jmax <= m.cols()));
145  res.resize(imax - imin, jmax - jmin);
146  for (size_type i = imin; i < imax; ++i)
147  for (size_type j = jmin; j < jmax; ++j) res(i - imin, j - jmin) = m(i, j);
148  }
149 
150  public:
153 
154  inline void setBoundsRow(const size_type &m, const size_type &M) {
155  imin = m;
156  imax = M;
157  }
158  inline void setBoundsCol(const size_type &m, const size_type &M) {
159  jmin = m;
160  jmax = M;
161  }
162 
163  inline void addSpecificCommands(Entity &ent,
164  Entity::CommandMap_t &commandMap) {
165  using namespace dynamicgraph::command;
166  std::string doc;
167 
168  boost::function<void(const size_type &, const size_type &)> setBoundsRow =
169  boost::bind(&MatrixSelector::setBoundsRow, this, _1, _2);
170  boost::function<void(const size_type &, const size_type &)> setBoundsCol =
171  boost::bind(&MatrixSelector::setBoundsCol, this, _1, _2);
172 
173  doc = docCommandVoid2("Set the bound on rows.", "size_type (min)",
174  "size_type (max)");
175  ADD_COMMAND("selecRows", makeCommandVoid2(ent, setBoundsRow, doc));
176 
177  doc = docCommandVoid2("Set the bound on cols [m,M[.", "size_type (min)",
178  "size_type (max)");
179  ADD_COMMAND("selecCols", makeCommandVoid2(ent, setBoundsCol, doc));
180  }
181 };
182 
183 /* ---------------------------------------------------------------------- */
184 struct MatrixColumnSelector : public UnaryOpHeader<dg::Matrix, dg::Vector> {
185  public:
186  inline void operator()(const Tin &m, Tout &res) const {
187  assert((imin <= imax) && (imax <= m.rows()));
188  assert(jcol < m.cols());
189 
190  res.resize(imax - imin);
191  for (size_type i = imin; i < imax; ++i) res(i - imin) = m(i, jcol);
192  }
193 
196  inline void selectCol(const size_type &m) { jcol = m; }
197  inline void setBoundsRow(const size_type &m, const size_type &M) {
198  imin = m;
199  imax = M;
200  }
201 
202  inline void addSpecificCommands(Entity &ent,
203  Entity::CommandMap_t &commandMap) {
204  using namespace dynamicgraph::command;
205  std::string doc;
206 
207  boost::function<void(const size_type &, const size_type &)> setBoundsRow =
208  boost::bind(&MatrixColumnSelector::setBoundsRow, this, _1, _2);
209  boost::function<void(const size_type &)> selectCol =
210  boost::bind(&MatrixColumnSelector::selectCol, this, _1);
211 
212  doc = docCommandVoid2("Set the bound on rows.", "size_type (min)",
213  "size_type (max)");
214  ADD_COMMAND("selecRows", makeCommandVoid2(ent, setBoundsRow, doc));
215 
216  doc = docCommandVoid1("Select the col to copy.", "size_type (col index)");
217  ADD_COMMAND("selecCols", makeCommandVoid1(ent, selectCol, doc));
218  }
219 };
220 
221 /* ---------------------------------------------------------------------- */
222 struct MatrixTranspose : public UnaryOpHeader<dg::Matrix, dg::Matrix> {
223  inline void operator()(const Tin &m, Tout &res) const { res = m.transpose(); }
224 };
225 
226 /* ---------------------------------------------------------------------- */
227 struct Diagonalizer : public UnaryOpHeader<Vector, Matrix> {
228  inline void operator()(const dg::Vector &r, dg::Matrix &res) {
229  res = r.asDiagonal();
230  }
231 
232  public:
233  Diagonalizer(void) : nbr(0), nbc(0) {}
234  std::size_t nbr, nbc;
235  inline void resize(const size_type &r, const size_type &c) {
236  nbr = r;
237  nbc = c;
238  }
239  inline void addSpecificCommands(Entity &ent,
240  Entity::CommandMap_t &commandMap) {
241  using namespace dynamicgraph::command;
242  std::string doc;
243 
244  boost::function<void(const size_type &, const size_type &)> resize =
245  boost::bind(&Diagonalizer::resize, this, _1, _2);
246 
247  doc = docCommandVoid2("Set output size.", "size_type (row)",
248  "size_type (col)");
249  ADD_COMMAND("resize", makeCommandVoid2(ent, resize, doc));
250  }
251 };
252 
253 /* ---------------------------------------------------------------------- */
254 /* --- INVERSION -------------------------------------------------------- */
255 /* ---------------------------------------------------------------------- */
256 
257 template <typename matrixgen>
258 struct Inverser : public UnaryOpHeader<matrixgen, matrixgen> {
261  inline void operator()(const Tin &m, Tout &res) const { res = m.inverse(); }
262 };
263 
264 struct Normalize : public UnaryOpHeader<dg::Vector, double> {
265  inline void operator()(const dg::Vector &m, double &res) const {
266  res = m.norm();
267  }
268 
269  inline std::string getDocString() const {
270  std::string docString(
271  "Computes the norm of a vector\n"
272  " - input vector\n"
273  " - output double");
274  return docString;
275  }
276 };
277 
278 struct InverserRotation : public UnaryOpHeader<MatrixRotation, MatrixRotation> {
279  inline void operator()(const Tin &m, Tout &res) const { res = m.transpose(); }
280 };
281 
283  : public UnaryOpHeader<VectorQuaternion, VectorQuaternion> {
284  inline void operator()(const Tin &m, Tout &res) const { res = m.conjugate(); }
285 };
286 
287 /* ----------------------------------------------------------------------- */
288 /* --- SE3/SO3 conversions ----------------------------------------------- */
289 /* ----------------------------------------------------------------------- */
290 
292  : public UnaryOpHeader<MatrixHomogeneous, dg::Vector> {
293  inline void operator()(const MatrixHomogeneous &M, dg::Vector &res) {
294  res.resize(6);
295  VectorUTheta r(M.linear());
296  res.head<3>() = M.translation();
297  res.tail<3>() = r.angle() * r.axis();
298  }
299 };
300 
301 struct SkewSymToVector : public UnaryOpHeader<Matrix, Vector> {
302  inline void operator()(const Matrix &M, Vector &res) {
303  res.resize(3);
304  res(0) = M(7);
305  res(1) = M(2);
306  res(2) = M(3);
307  }
308 };
309 
311  : public UnaryOpHeader<Vector, MatrixHomogeneous> {
312  inline void operator()(const dg::Vector &v, MatrixHomogeneous &res) {
313  assert(v.size() >= 6);
314  res.translation() = v.head<3>();
315  double theta = v.tail<3>().norm();
316  if (theta > 0)
317  res.linear() = Eigen::AngleAxisd(theta, v.tail<3>() / theta).matrix();
318  else
319  res.linear().setIdentity();
320  }
321 };
322 
324  : public UnaryOpHeader<dg::Vector, MatrixHomogeneous> {
325  void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
326  Mres.translation() = vect.head<3>();
327  Mres.linear().row(0) = vect.segment(3, 3);
328  Mres.linear().row(1) = vect.segment(6, 3);
329  Mres.linear().row(2) = vect.segment(9, 3);
330  }
331 };
332 
334  : public UnaryOpHeader<MatrixHomogeneous, dg::Vector> {
335  void operator()(const MatrixHomogeneous &M, dg::Vector &res) {
336  res.resize(12);
337  res.head<3>() = M.translation();
338  res.segment(3, 3) = M.linear().row(0);
339  res.segment(6, 3) = M.linear().row(1);
340  res.segment(9, 3) = M.linear().row(2);
341  }
342 };
343 
345  : public UnaryOpHeader<Vector, MatrixHomogeneous> {
346  void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
347  Mres.translation() = vect.head<3>();
348  Mres.linear() = VectorQuaternion(vect.tail<4>()).toRotationMatrix();
349  }
350 };
351 
353  : public UnaryOpHeader<MatrixHomogeneous, Vector> {
354  inline void operator()(const MatrixHomogeneous &M, Vector &res) {
355  res.resize(7);
356  res.head<3>() = M.translation();
357  Eigen::Map<VectorQuaternion> q(res.tail<4>().data());
358  q = M.linear();
359  }
360 };
361 
363  : public UnaryOpHeader<MatrixHomogeneous, Vector> {
364  inline void operator()(const MatrixHomogeneous &M, dg::Vector &res) {
365  VectorRollPitchYaw r = (M.linear().eulerAngles(2, 1, 0)).reverse();
366  dg::Vector t(3);
367  t = M.translation();
368  res.resize(6);
369  for (std::size_t i = 0; i < 3; ++i) res(i) = t(i);
370  for (std::size_t i = 0; i < 3; ++i) res(i + 3) = r(i);
371  }
372 };
373 
375  : public UnaryOpHeader<Vector, MatrixHomogeneous> {
376  inline void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
378  for (std::size_t i = 0; i < 3; ++i) r(i) = vect(i + 3);
379  MatrixRotation R = (Eigen::AngleAxisd(r(2), Eigen::Vector3d::UnitZ()) *
380  Eigen::AngleAxisd(r(1), Eigen::Vector3d::UnitY()) *
381  Eigen::AngleAxisd(r(0), Eigen::Vector3d::UnitX()))
382  .toRotationMatrix();
383 
384  dg::Vector t(3);
385  for (std::size_t i = 0; i < 3; ++i) t(i) = vect(i);
386 
387  // buildFrom(R,t);
388  Mres = Eigen::Translation3d(t) * R;
389  }
390 };
391 
392 struct PoseRollPitchYawToPoseUTheta : public UnaryOpHeader<Vector, Vector> {
393  inline void operator()(const dg::Vector &vect, dg::Vector &vectres) {
395  for (std::size_t i = 0; i < 3; ++i) r(i) = vect(i + 3);
396  MatrixRotation R = (Eigen::AngleAxisd(r(2), Eigen::Vector3d::UnitZ()) *
397  Eigen::AngleAxisd(r(1), Eigen::Vector3d::UnitY()) *
398  Eigen::AngleAxisd(r(0), Eigen::Vector3d::UnitX()))
399  .toRotationMatrix();
400 
401  VectorUTheta rrot(R);
402 
403  vectres.resize(6);
404  for (std::size_t i = 0; i < 3; ++i) {
405  vectres(i) = vect(i);
406  vectres(i + 3) = rrot.angle() * rrot.axis()(i);
407  }
408  }
409 };
410 
411 struct HomoToMatrix : public UnaryOpHeader<MatrixHomogeneous, Matrix> {
412  inline void operator()(const MatrixHomogeneous &M, dg::Matrix &res) {
413  res = M.matrix();
414  }
415 };
416 
417 struct MatrixToHomo : public UnaryOpHeader<Matrix, MatrixHomogeneous> {
418  inline void operator()(const Eigen::Matrix<double, 4, 4> &M,
419  MatrixHomogeneous &res) {
420  res = M;
421  }
422 };
423 
424 struct HomoToTwist : public UnaryOpHeader<MatrixHomogeneous, MatrixTwist> {
425  inline void operator()(const MatrixHomogeneous &M, MatrixTwist &res) {
426  Eigen::Vector3d _t = M.translation();
427  MatrixRotation R(M.linear());
428  Eigen::Matrix3d Tx;
429  Tx << 0, -_t(2), _t(1), _t(2), 0, -_t(0), -_t(1), _t(0), 0;
430 
431  Eigen::Matrix3d sk;
432  sk = Tx * R;
433  res.block<3, 3>(0, 0) = R;
434  res.block<3, 3>(0, 3) = sk;
435  res.block<3, 3>(3, 0) = Eigen::Matrix3d::Zero();
436  res.block<3, 3>(3, 3) = R;
437  }
438 };
439 
441  : public UnaryOpHeader<MatrixHomogeneous, MatrixRotation> {
442  inline void operator()(const MatrixHomogeneous &M, MatrixRotation &res) {
443  res = M.linear();
444  }
445 };
446 
447 struct MatrixHomoToPose : public UnaryOpHeader<MatrixHomogeneous, Vector> {
448  inline void operator()(const MatrixHomogeneous &M, Vector &res) {
449  res.resize(3);
450  res = M.translation();
451  }
452 };
453 
454 struct RPYToMatrix : public UnaryOpHeader<VectorRollPitchYaw, MatrixRotation> {
455  inline void operator()(const VectorRollPitchYaw &r, MatrixRotation &res) {
456  res = (Eigen::AngleAxisd(r(2), Eigen::Vector3d::UnitZ()) *
457  Eigen::AngleAxisd(r(1), Eigen::Vector3d::UnitY()) *
458  Eigen::AngleAxisd(r(0), Eigen::Vector3d::UnitX()))
459  .toRotationMatrix();
460  }
461 };
462 
463 struct MatrixToRPY : public UnaryOpHeader<MatrixRotation, VectorRollPitchYaw> {
464  inline void operator()(const MatrixRotation &r, VectorRollPitchYaw &res) {
465  res = (r.eulerAngles(2, 1, 0)).reverse();
466  }
467 };
468 
470  : public UnaryOpHeader<VectorRollPitchYaw, VectorQuaternion> {
471  inline void operator()(const VectorRollPitchYaw &r, VectorQuaternion &res) {
472  res = (Eigen::AngleAxisd(r(2), Eigen::Vector3d::UnitZ()) *
473  Eigen::AngleAxisd(r(1), Eigen::Vector3d::UnitY()) *
474  Eigen::AngleAxisd(r(0), Eigen::Vector3d::UnitX()))
475  .toRotationMatrix();
476  }
477 };
478 
480  : public UnaryOpHeader<VectorQuaternion, VectorRollPitchYaw> {
481  inline void operator()(const VectorQuaternion &r, VectorRollPitchYaw &res) {
482  res = (r.toRotationMatrix().eulerAngles(2, 1, 0)).reverse();
483  }
484 };
485 
487  : public UnaryOpHeader<VectorQuaternion, MatrixRotation> {
488  inline void operator()(const VectorQuaternion &r, MatrixRotation &res) {
489  res = r.toRotationMatrix();
490  }
491 };
492 
494  : public UnaryOpHeader<MatrixRotation, VectorQuaternion> {
495  inline void operator()(const MatrixRotation &r, VectorQuaternion &res) {
496  res = r;
497  }
498 };
499 
500 struct MatrixToUTheta : public UnaryOpHeader<MatrixRotation, VectorUTheta> {
501  inline void operator()(const MatrixRotation &r, VectorUTheta &res) {
502  res = r;
503  }
504 };
505 
507  : public UnaryOpHeader<VectorUTheta, VectorQuaternion> {
508  inline void operator()(const VectorUTheta &r, VectorQuaternion &res) {
509  res = r;
510  }
511 };
512 
513 template <typename TypeIn1, typename TypeIn2, typename TypeOut>
515  typedef TypeIn1 Tin1;
516  typedef TypeIn2 Tin2;
517  typedef TypeOut Tout;
518  inline static std::string nameTypeIn1(void) {
520  }
521  inline static std::string nameTypeIn2(void) {
523  }
524  inline static std::string nameTypeOut(void) {
526  }
528  inline std::string getDocString() const {
529  return std::string(
530  "Undocumented binary operator\n"
531  " - input ") +
532  nameTypeIn1() +
533  std::string(
534  "\n"
535  " - ") +
536  nameTypeIn2() +
537  std::string(
538  "\n"
539  " - output ") +
540  nameTypeOut() + std::string("\n");
541  }
542 };
543 
544 } /* namespace sot */
545 } /* namespace dynamicgraph */
546 
547 /* ---------------------------------------------------------------------------*/
548 /* ---------------------------------------------------------------------------*/
549 /* ---------------------------------------------------------------------------*/
550 
551 namespace dynamicgraph {
552 namespace sot {
553 
554 /* --- MULTIPLICATION --------------------------------------------------- */
555 
556 template <typename F, typename E>
557 struct Multiplier_FxE__E : public BinaryOpHeader<F, E, E> {
558  inline void operator()(const F &f, const E &e, E &res) const { res = f * e; }
559 };
560 
561 template <>
562 inline void
565  const dynamicgraph::Vector &e, dynamicgraph::Vector &res) const {
566  res = f.matrix() * e;
567 }
568 
569 template <>
571  const double &x, const dynamicgraph::Vector &v,
572  dynamicgraph::Vector &res) const {
573  res = v;
574  res *= x;
575 }
576 
585 
586 /* --- SUBSTRACTION ----------------------------------------------------- */
587 template <typename T>
588 struct Substraction : public BinaryOpHeader<T, T, T> {
589  inline void operator()(const T &v1, const T &v2, T &r) const {
590  r = v1;
591  r -= v2;
592  }
593 };
594 
595 /* --- STACK ------------------------------------------------------------ */
597  : public BinaryOpHeader<dynamicgraph::Vector, dynamicgraph::Vector,
598  dynamicgraph::Vector> {
599  public:
600  size_type v1min, v1max;
601  size_type v2min, v2max;
602  inline void operator()(const dynamicgraph::Vector &v1,
603  const dynamicgraph::Vector &v2,
604  dynamicgraph::Vector &res) const {
605  assert((v1max >= v1min) && (v1.size() >= v1max));
606  assert((v2max >= v2min) && (v2.size() >= v2max));
607 
608  const size_type v1size = v1max - v1min, v2size = v2max - v2min;
609  res.resize(v1size + v2size);
610  for (size_type i = 0; i < v1size; ++i) {
611  res(i) = v1(i + v1min);
612  }
613  for (size_type i = 0; i < v2size; ++i) {
614  res(v1size + i) = v2(i + v2min);
615  }
616  }
617 
618  inline void selec1(const size_type &m, const size_type M) {
619  v1min = m;
620  v1max = M;
621  }
622  inline void selec2(const size_type &m, const size_type M) {
623  v2min = m;
624  v2max = M;
625  }
626 
627  inline void addSpecificCommands(Entity &ent,
628  Entity::CommandMap_t &commandMap) {
629  using namespace dynamicgraph::command;
630  std::string doc;
631 
632  boost::function<void(const size_type &, const size_type &)> selec1 =
633  boost::bind(&VectorStack::selec1, this, _1, _2);
634  boost::function<void(const size_type &, const size_type &)> selec2 =
635  boost::bind(&VectorStack::selec2, this, _1, _2);
636 
637  ADD_COMMAND("selec1",
639  ent, selec1,
640  docCommandVoid2("set the min and max of selection.",
641  "size_type (imin)", "size_type (imax)")));
642  ADD_COMMAND("selec2",
644  ent, selec2,
645  docCommandVoid2("set the min and max of selection.",
646  "size_type (imin)", "size_type (imax)")));
647  }
648 };
649 
650 /* ---------------------------------------------------------------------- */
651 
652 struct Composer
653  : public BinaryOpHeader<dynamicgraph::Matrix, dynamicgraph::Vector,
654  MatrixHomogeneous> {
655  inline void operator()(const dynamicgraph::Matrix &R,
656  const dynamicgraph::Vector &t,
657  MatrixHomogeneous &H) const {
658  H.linear() = R;
659  H.translation() = t;
660  }
661 };
662 
663 /* --- CONVOLUTION PRODUCT ---------------------------------------------- */
665  : public BinaryOpHeader<dynamicgraph::Vector, dynamicgraph::Matrix,
666  dynamicgraph::Vector> {
667  typedef std::deque<dynamicgraph::Vector> MemoryType;
669 
670  inline void convolution(const MemoryType &f1, const dynamicgraph::Matrix &f2,
671  dynamicgraph::Vector &res) {
672  const Vector::Index nconv = (Vector::Index)f1.size(), nsig = f2.rows();
673  sotDEBUG(15) << "Size: " << nconv << "x" << nsig << std::endl;
674  if (nconv > f2.cols()) return; // TODO: error, this should not happen
675 
676  res.resize(nsig);
677  res.fill(0);
678  std::size_t j = 0;
679  for (MemoryType::const_iterator iter = f1.begin(); iter != f1.end();
680  iter++) {
681  const dynamicgraph::Vector &s_tau = *iter;
682  sotDEBUG(45) << "Sig" << j << ": " << s_tau;
683  if (s_tau.size() != nsig) return; // TODO: error throw;
684  for (size_type i = 0; i < nsig; ++i) {
685  res(i) += f2(i, j) * s_tau(i);
686  }
687  j++;
688  }
689  }
690  inline void operator()(const dynamicgraph::Vector &v1,
691  const dynamicgraph::Matrix &m2,
692  dynamicgraph::Vector &res) {
693  memory.push_front(v1);
694  while ((Vector::Index)memory.size() > m2.cols()) memory.pop_back();
695  convolution(memory, m2, res);
696  }
697 };
698 
699 /* --- BOOLEAN REDUCTION ------------------------------------------------ */
700 
701 template <typename T>
702 struct Comparison : public BinaryOpHeader<T, T, bool> {
703  inline void operator()(const T &a, const T &b, bool &res) const {
704  res = (a < b);
705  }
706  inline std::string getDocString() const {
708  return std::string(
709  "Comparison of inputs:\n"
710  " - input ") +
711  Base::nameTypeIn1() +
712  std::string(
713  "\n"
714  " - ") +
715  Base::nameTypeIn2() +
716  std::string(
717  "\n"
718  " - output ") +
719  Base::nameTypeOut() +
720  std::string(
721  "\n"
722  " sout = ( sin1 < sin2 )\n");
723  }
724 };
725 
726 template <typename T1, typename T2 = T1>
727 struct MatrixComparison : public BinaryOpHeader<T1, T2, bool> {
728  // TODO T1 or T2 could be a scalar type.
729  inline void operator()(const T1 &a, const T2 &b, bool &res) const {
730  if (equal && any)
731  res = (a.array() <= b.array()).any();
732  else if (equal && !any)
733  res = (a.array() <= b.array()).all();
734  else if (!equal && any)
735  res = (a.array() < b.array()).any();
736  else if (!equal && !any)
737  res = (a.array() < b.array()).all();
738  }
739  inline std::string getDocString() const {
741  return std::string(
742  "Comparison of inputs:\n"
743  " - input ") +
744  Base::nameTypeIn1() +
745  std::string(
746  "\n"
747  " - ") +
748  Base::nameTypeIn2() +
749  std::string(
750  "\n"
751  " - output ") +
752  Base::nameTypeOut() +
753  std::string(
754  "\n"
755  " sout = ( sin1 < sin2 ).op()\n") +
756  std::string(
757  "\n"
758  " where op is either any (default) or all. The "
759  "comparison can be made <=.\n");
760  }
761  MatrixComparison() : any(true), equal(false) {}
762  inline void addSpecificCommands(Entity &ent,
763  Entity::CommandMap_t &commandMap) {
764  using namespace dynamicgraph::command;
765  ADD_COMMAND(
766  "setTrueIfAny",
767  makeDirectSetter(ent, &any, docDirectSetter("trueIfAny", "bool")));
768  ADD_COMMAND(
769  "getTrueIfAny",
770  makeDirectGetter(ent, &any, docDirectGetter("trueIfAny", "bool")));
771  ADD_COMMAND("setEqual", makeDirectSetter(ent, &equal,
772  docDirectSetter("equal", "bool")));
773  ADD_COMMAND("getEqual", makeDirectGetter(ent, &equal,
774  docDirectGetter("equal", "bool")));
775  }
776  bool any, equal;
777 };
778 
779 } /* namespace sot */
780 } /* namespace dynamicgraph */
781 
782 namespace dynamicgraph {
783 namespace sot {
784 
785 template <typename T>
786 struct WeightedAdder : public BinaryOpHeader<T, T, T> {
787  public:
788  double gain1, gain2;
789  inline void operator()(const T &v1, const T &v2, T &res) const {
790  res = v1;
791  res *= gain1;
792  res += gain2 * v2;
793  }
794 
795  inline void addSpecificCommands(Entity &ent,
796  Entity::CommandMap_t &commandMap) {
797  using namespace dynamicgraph::command;
798  std::string doc;
799 
800  ADD_COMMAND(
801  "setGain1",
802  makeDirectSetter(ent, &gain1, docDirectSetter("gain1", "double")));
803  ADD_COMMAND(
804  "setGain2",
805  makeDirectSetter(ent, &gain2, docDirectSetter("gain2", "double")));
806  ADD_COMMAND(
807  "getGain1",
808  makeDirectGetter(ent, &gain1, docDirectGetter("gain1", "double")));
809  ADD_COMMAND(
810  "getGain2",
811  makeDirectGetter(ent, &gain2, docDirectGetter("gain2", "double")));
812  }
813 
814  inline std::string getDocString() const {
815  return std::string("Weighted Combination of inputs : \n - gain{1|2} gain.");
816  }
817 };
818 
819 } // namespace sot
820 } // namespace dynamicgraph
821 
822 namespace dynamicgraph {
823 namespace sot {
824 template <typename Tin, typename Tout, typename Time>
827 }
828 template <typename Tin, typename Tout, typename Time>
831 }
832 
833 template <typename TypeIn, typename TypeOut>
835  typedef TypeIn Tin;
836  typedef TypeOut Tout;
837  inline static std::string nameTypeIn(void) {
839  }
840  inline static std::string nameTypeOut(void) {
842  }
843  template <typename Op>
845  inline void updateSignalNumber(const size_type &) {}
846  inline std::string getDocString() const {
847  return std::string(
848  "Undocumented variadic operator\n"
849  " - input " +
850  nameTypeIn() +
851  "\n"
852  " - output " +
853  nameTypeOut() + "\n");
854  }
855 };
856 
857 /* --- VectorMix ------------------------------------------------------------ */
858 struct VectorMix : public VariadicOpHeader<Vector, Vector> {
859  public:
861  struct segment_t {
863  std::size_t sigIdx;
865  : index(i), size(s), sigIdx(sig) {}
866  };
867  typedef std::vector<segment_t> segments_t;
870  inline void operator()(const std::vector<const Vector *> &vs,
871  Vector &res) const {
872  res = *vs[0];
873  for (std::size_t i = 0; i < idxs.size(); ++i) {
874  const segment_t &s = idxs[i];
875  if (s.sigIdx >= vs.size())
876  throw std::invalid_argument("Index out of range in VectorMix");
877  res.segment(s.index, s.size) = *vs[s.sigIdx];
878  }
879  }
880 
881  inline void addSelec(const size_type &sigIdx, const size_type &i,
882  const size_type &s) {
883  idxs.push_back(segment_t(i, s, sigIdx));
884  }
885 
886  inline void initialize(Base *ent, Entity::CommandMap_t &commandMap) {
887  using namespace dynamicgraph::command;
888  entity = ent;
889 
890  ent->addSignal("default");
891 
892  boost::function<void(const size_type &, const size_type &,
893  const sigtime_t &)>
894  selec = boost::bind(&VectorMix::addSelec, this, _1, _2, _3);
895 
896  commandMap.insert(std::make_pair(
897  "addSelec",
898  makeCommandVoid3<Base, size_type, size_type, sigtime_t>(
899  *ent, selec,
900  docCommandVoid3("add selection from a vector.",
901  "size_type (signal index >= 1)",
902  "size_type (index)", "size_type (size)"))));
903  }
904 };
905 
906 /* --- ADDITION --------------------------------------------------------- */
907 template <typename T>
908 struct AdderVariadic : public VariadicOpHeader<T, T> {
910 
913 
914  AdderVariadic() : coeffs() {}
915  inline void operator()(const std::vector<const T *> &vs, T &res) const {
916  assert(vs.size() == (std::size_t)coeffs.size());
917  if (vs.size() == 0) return;
918  res = coeffs[0] * (*vs[0]);
919  for (std::size_t i = 1; i < vs.size(); ++i) res += coeffs[i] * (*vs[i]);
920  }
921 
922  inline void setCoeffs(const Vector &c) {
923  if (entity->getSignalNumber() != c.size())
924  throw std::invalid_argument("Invalid coefficient size.");
925  coeffs = c;
926  }
927  inline void updateSignalNumber(const size_type &n) {
928  coeffs = Vector::Ones(n);
929  }
930 
931  inline void initialize(Base *ent, Entity::CommandMap_t &) {
932  entity = ent;
933  entity->setSignalNumber(2);
934  }
935 
936  inline std::string getDocString() const {
937  return "Linear combination of inputs\n"
938  " - input " +
940  "\n"
941  " - output " +
943  "\n"
944  " sout = sum ([coeffs[i] * sin[i] for i in range(n) ])\n"
945  " Coefficients are set by commands, default value is 1.\n";
946  }
947 };
948 
949 /* --- MULTIPLICATION --------------------------------------------------- */
950 template <typename T>
951 struct Multiplier : public VariadicOpHeader<T, T> {
953 
954  inline void operator()(const std::vector<const T *> &vs, T &res) const {
955  if (vs.size() == 0)
956  setIdentity(res);
957  else {
958  res = *vs[0];
959  for (std::size_t i = 1; i < vs.size(); ++i) res *= *vs[i];
960  }
961  }
962 
963  inline void setIdentity(T &res) const { res.setIdentity(); }
964 
965  inline void initialize(Base *ent, Entity::CommandMap_t &) {
966  ent->setSignalNumber(2);
967  }
968 };
969 template <>
970 inline void Multiplier<double>::setIdentity(double &res) const {
971  res = 1;
972 }
973 template <>
975  const std::vector<const MatrixHomogeneous *> &vs,
976  MatrixHomogeneous &res) const {
977  if (vs.size() == 0)
978  setIdentity(res);
979  else {
980  res = *vs[0];
981  for (std::size_t i = 1; i < vs.size(); ++i) res = res * *vs[i];
982  }
983 }
984 template <>
986  const std::vector<const Vector *> &vs, Vector &res) const {
987  if (vs.size() == 0)
988  res.resize(0);
989  else {
990  res = *vs[0];
991  for (std::size_t i = 1; i < vs.size(); ++i) res.array() *= vs[i]->array();
992  }
993 }
994 
995 /* --- BOOLEAN --------------------------------------------------------- */
996 template <size_type operation>
997 struct BoolOp : public VariadicOpHeader<bool, bool> {
999 
1000  inline void operator()(const std::vector<const bool *> &vs, bool &res) const {
1001  // TODO computation could be optimized with lazy evaluation of the
1002  // signals. When the output result is know, the remaining signals are
1003  // not computed.
1004  if (vs.size() == 0) return;
1005  res = *vs[0];
1006  for (std::size_t i = 1; i < vs.size(); ++i) switch (operation) {
1007  case 0:
1008  if (!res) return;
1009  res = *vs[i];
1010  break;
1011  case 1:
1012  if (res) return;
1013  res = *vs[i];
1014  break;
1015  }
1016  }
1017 };
1018 
1019 } // namespace sot
1020 } // namespace dynamicgraph
1021 
1022 /* --- TODO ------------------------------------------------------------------*/
1023 // The following commented lines are sot-v1 entities that are still waiting
1024 // for conversion. Help yourself!
1025 
1026 // /* --------------------------------------------------------------------------
1027 // */
1028 
1029 // struct WeightedDirection
1030 // {
1031 // public:
1032 // void operator()( const dynamicgraph::Vector& v1,const dynamicgraph::Vector&
1033 // v2,dynamicgraph::Vector& res ) const
1034 // {
1035 // const double norm1 = v1.norm();
1036 // const double norm2 = v2.norm();
1037 // res=v2; res*=norm1;
1038 // res*= (1/norm2);
1039 // }
1040 // };
1041 // typedef BinaryOp< Vector,Vector,Vector,WeightedDirection > weightdir;
1042 // SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(weightdir,vector,weight_dir,"WeightDir")
1043 
1044 // /* --------------------------------------------------------------------------
1045 // */
1046 
1047 // struct Nullificator
1048 // {
1049 // public:
1050 // void operator()( const dynamicgraph::Vector& v1,const dynamicgraph::Vector&
1051 // v2,dynamicgraph::Vector& res ) const
1052 // {
1053 // const std::size_t s = std::max( v1.size(),v2.size() );
1054 // res.resize(s);
1055 // for( std::size_t i=0;i<s;++i )
1056 // {
1057 // if( v1(i)>v2(i) ) res(i)=v1(i)-v2(i);
1058 // else if( v1(i)<-v2(i) ) res(i)=v1(i)+v2(i);
1059 // else res(i)=0;
1060 // }
1061 // }
1062 // };
1063 // typedef BinaryOp< Vector,Vector,Vector,Nullificator > vectNil;
1064 // SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(vectNil,vector,vectnil_,"Nullificator")
1065 
1066 // /* --------------------------------------------------------------------------
1067 // */
1068 
1069 // struct VirtualSpring
1070 // {
1071 // public:
1072 // double spring;
1073 
1074 // void operator()( const dynamicgraph::Vector& pos,const
1075 // dynamicgraph::Vector& ref,dynamicgraph::Vector& res ) const
1076 // {
1077 // double norm = ref.norm();
1078 // double dist = ref.scalarProduct(pos) / (norm*norm);
1079 
1080 // res.resize( ref.size() );
1081 // res = ref; res *= dist; res -= pos;
1082 // res *= spring;
1083 // }
1084 // };
1085 // typedef BinaryOp< Vector,Vector,Vector,VirtualSpring > virtspring;
1086 // SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD
1087 // (virtspring,vector,virtspring_,
1088 // "VirtualSpring"
1089 // ,else if( cmdLine=="spring" ){ CMDARGS_INOUT(op.spring); }
1090 // ,"VirtualSpring<pos,ref> compute the virtual force of a spring attache "
1091 // "to the reference line <ref>. The eq is: k.(<ref|pos>/<ref|ref>.ref-pos)"
1092 // "Params:\n - spring: get/set the spring factor.")
dynamicgraph::sot::Inverser::Tout
UnaryOpHeader< matrixgen, matrixgen >::Tout Tout
Definition: operator.hh:260
dynamicgraph::sot::Composer::operator()
void operator()(const dynamicgraph::Matrix &R, const dynamicgraph::Vector &t, MatrixHomogeneous &H) const
Definition: operator.hh:655
m
float m
dynamicgraph::sot::VariadicOpHeader
Definition: operator.hh:834
dynamicgraph::sot::VariadicAbstract::getTypeInName
static std::string getTypeInName(void)
Definition: operator.hh:825
dynamicgraph::sot::Comparison
Definition: operator.hh:702
dynamicgraph::sot::VariadicOpHeader::Tout
TypeOut Tout
Definition: operator.hh:836
dynamicgraph::sot::VectorComponent::operator()
void operator()(const Tin &m, double &res) const
Definition: operator.hh:113
dynamicgraph::sot::BoolOp::Base
VariadicOp< BoolOp > Base
Definition: operator.hh:998
dynamicgraph::sot::VectorSelecter::size
Vector::Index size
Definition: operator.hh:81
dynamicgraph::sot::HomoToTwist::operator()
void operator()(const MatrixHomogeneous &M, MatrixTwist &res)
Definition: operator.hh:425
dynamicgraph::sot::Diagonalizer
Definition: operator.hh:227
dynamicgraph::sot::WeightedAdder
Definition: operator.hh:786
dynamicgraph::sot::AdderVariadic::initialize
void initialize(Base *ent, Entity::CommandMap_t &)
Definition: operator.hh:931
input
input
dynamicgraph::sot::VectorQuaternion
Eigen::Quaternion< double > SOT_CORE_EXPORT VectorQuaternion
Definition: matrix-geometry.hh:78
dynamicgraph::sot::Multiplier::Base
VariadicOp< Multiplier > Base
Definition: operator.hh:952
dynamicgraph::sot::MatrixHomoToSE3Vector::operator()
void operator()(const MatrixHomogeneous &M, dg::Vector &res)
Definition: operator.hh:335
dynamicgraph::sot::WeightedAdder::gain2
double gain2
Definition: operator.hh:788
dynamicgraph::sot::VectorStack::v2min
size_type v2min
Definition: operator.hh:601
dynamicgraph::sot::PoseRollPitchYawToMatrixHomo
Definition: operator.hh:374
dynamicgraph::sot::VectorStack::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:627
callback
callback
dynamicgraph::sot::VectorMix::initialize
void initialize(Base *ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:886
factory.hh
dynamicgraph::sot::MatrixHomoToPoseQuaternion
Definition: operator.hh:352
dynamicgraph::sot::RPYToQuaternion
Definition: operator.hh:469
dynamicgraph::sot::VectorSelecter::VectorSelecter
VectorSelecter()
Definition: operator.hh:108
dynamicgraph::sot::Multiplier_matrixTwist_vector
Multiplier_FxE__E< MatrixTwist, dynamicgraph::Vector > Multiplier_matrixTwist_vector
Definition: operator.hh:584
dynamicgraph::sot::MatrixHomogeneous
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
Definition: matrix-geometry.hh:75
dynamicgraph::sot::AdderVariadic::updateSignalNumber
void updateSignalNumber(const size_type &n)
Definition: operator.hh:927
dynamicgraph::sot::UnaryOpHeader
Definition: operator.hh:39
dynamicgraph::sot::MatrixSelector
Definition: operator.hh:141
binary-op.hh
dynamicgraph::sot::UnaryOpHeader::addSpecificCommands
void addSpecificCommands(Entity &, Entity::CommandMap_t &)
Definition: operator.hh:48
dynamicgraph::sot::VectorMix::segment_t
Definition: operator.hh:861
dynamicgraph::sot::Diagonalizer::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:239
dynamicgraph::sot::MatrixHomoToPoseQuaternion::operator()
void operator()(const MatrixHomogeneous &M, Vector &res)
Definition: operator.hh:354
unary-op.hh
dynamicgraph
dynamicgraph::sot::MatrixComparison
Definition: operator.hh:727
dynamicgraph::sot::VectorSelecter
Definition: operator.hh:64
dynamicgraph::sot::RPYToMatrix
Definition: operator.hh:454
dynamicgraph::sot::Comparison::operator()
void operator()(const T &a, const T &b, bool &res) const
Definition: operator.hh:703
c
Vec3f c
index
index
dynamicgraph::sot::HomoToRotation
Definition: operator.hh:440
dynamicgraph::command
i
int i
dynamicgraph::sot::UThetaToQuaternion::operator()
void operator()(const VectorUTheta &r, VectorQuaternion &res)
Definition: operator.hh:508
dynamicgraph::sot::ConvolutionTemporal::memory
MemoryType memory
Definition: operator.hh:668
dynamicgraph::sot::MatrixColumnSelector::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:202
dynamicgraph::sot::BinaryOpHeader::addSpecificCommands
void addSpecificCommands(Entity &, Entity::CommandMap_t &)
Definition: operator.hh:527
dynamicgraph::sot::MatrixColumnSelector::selectCol
void selectCol(const size_type &m)
Definition: operator.hh:196
Base
BVNodeBase Base
dynamicgraph::Entity
dynamicgraph::sot::MatrixSelector::operator()
void operator()(const Matrix &m, Matrix &res) const
Definition: operator.hh:142
dynamicgraph::sot::Multiplier_double_vector
Multiplier_FxE__E< double, dynamicgraph::Vector > Multiplier_double_vector
Definition: operator.hh:578
dynamicgraph::sot::MatrixToHomo::operator()
void operator()(const Eigen::Matrix< double, 4, 4 > &M, MatrixHomogeneous &res)
Definition: operator.hh:418
dynamicgraph::sot::VectorSelecter::idxs
segments_t idxs
Definition: operator.hh:80
dynamicgraph::sot::VectorComponent::index
size_type index
Definition: operator.hh:118
dynamicgraph::sot::Comparison::getDocString
std::string getDocString() const
Definition: operator.hh:706
dynamicgraph::sot::WeightedAdder::getDocString
std::string getDocString() const
Definition: operator.hh:814
dynamicgraph::sot::QuaternionToRPY::operator()
void operator()(const VectorQuaternion &r, VectorRollPitchYaw &res)
Definition: operator.hh:481
dynamicgraph::sot::VectorMix::entity
Base * entity
Definition: operator.hh:868
dynamicgraph::sot::InverserQuaternion
Definition: operator.hh:282
dynamicgraph::sot::VectorStack
Definition: operator.hh:596
dynamicgraph::sot::Diagonalizer::Diagonalizer
Diagonalizer(void)
Definition: operator.hh:233
dynamicgraph::sot::VectorComponent
Definition: operator.hh:112
dynamicgraph::sot::HomoToMatrix
Definition: operator.hh:411
dynamicgraph::sot::MatrixHomoToSE3Vector
Definition: operator.hh:333
dynamicgraph::Matrix
Eigen::MatrixXd Matrix
dynamicgraph::sot::VectorMix::segment_t::sigIdx
std::size_t sigIdx
Definition: operator.hh:863
dynamicgraph::sot::VariadicAbstract::setSignalNumber
void setSignalNumber(const size_type &n)
Definition: variadic-op.hh:89
R
R
dynamicgraph::sot::MatrixColumnSelector
Definition: operator.hh:184
dynamicgraph::sot::VectorSelecter::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:92
dynamicgraph::sot::PoseQuaternionToMatrixHomo::operator()
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres)
Definition: operator.hh:346
dynamicgraph::sot::Multiplier_matrixHomo_vector
Multiplier_FxE__E< MatrixHomogeneous, dynamicgraph::Vector > Multiplier_matrixHomo_vector
Definition: operator.hh:582
dynamicgraph::sot::BoolOp::operator()
void operator()(const std::vector< const bool * > &vs, bool &res) const
Definition: operator.hh:1000
dynamicgraph::sot::MatrixSelector::setBoundsCol
void setBoundsCol(const size_type &m, const size_type &M)
Definition: operator.hh:158
f
void f(void)
Definition: test_mailbox.cpp:33
dynamicgraph::sot::BinaryOpHeader::Tin1
TypeIn1 Tin1
Definition: operator.hh:515
dynamicgraph::sot::RPYToQuaternion::operator()
void operator()(const VectorRollPitchYaw &r, VectorQuaternion &res)
Definition: operator.hh:471
dynamicgraph::sot::AdderVariadic::AdderVariadic
AdderVariadic()
Definition: operator.hh:914
dynamicgraph::sot::BinaryOpHeader::nameTypeIn2
static std::string nameTypeIn2(void)
Definition: operator.hh:521
b
Vec3f b
dynamicgraph::sot::VectorMix::addSelec
void addSelec(const size_type &sigIdx, const size_type &i, const size_type &s)
Definition: operator.hh:881
dynamicgraph::sot::Normalize
Definition: operator.hh:264
dynamicgraph::sot::InverserRotation::operator()
void operator()(const Tin &m, Tout &res) const
Definition: operator.hh:279
r
FCL_REAL r
dynamicgraph::sot::MatrixSelector::imin
size_type imin
Definition: operator.hh:151
dynamicgraph::sot::Inverser::Tin
UnaryOpHeader< matrixgen, matrixgen >::Tin Tin
Definition: operator.hh:259
debug.hh
makeDirectGetter
DirectGetter< E, T > * makeDirectGetter(E &entity, T *ptr, const std::string &docString)
dynamicgraph::sot::AdderVariadic::operator()
void operator()(const std::vector< const T * > &vs, T &res) const
Definition: operator.hh:915
res
res
dynamicgraph::sot::MatrixToQuaternion
Definition: operator.hh:493
s
s
dynamicgraph::sot::VectorStack::operator()
void operator()(const dynamicgraph::Vector &v1, const dynamicgraph::Vector &v2, dynamicgraph::Vector &res) const
Definition: operator.hh:602
dynamicgraph::sot::VectorMix::segment_t::segment_t
segment_t(Vector::Index i, Vector::Index s, std::size_t sig)
Definition: operator.hh:864
dynamicgraph::sot::PoseQuaternionToMatrixHomo
Definition: operator.hh:344
dynamicgraph::sot::VectorRollPitchYaw
Eigen::Vector3d SOT_CORE_EXPORT VectorRollPitchYaw
Definition: matrix-geometry.hh:80
dynamicgraph::sot::MatrixTranspose::operator()
void operator()(const Tin &m, Tout &res) const
Definition: operator.hh:223
dynamicgraph::command::docCommandVoid1
std::string docCommandVoid1(const std::string &doc, const std::string &type)
dynamicgraph::sot::MatrixColumnSelector::jcol
size_type jcol
Definition: operator.hh:195
dynamicgraph::sot::Normalize::operator()
void operator()(const dg::Vector &m, double &res) const
Definition: operator.hh:265
dynamicgraph::sot::UnaryOpHeader::getDocString
std::string getDocString() const
Definition: operator.hh:49
dynamicgraph::sot::MatrixToRPY
Definition: operator.hh:463
dynamicgraph::sot::VariadicAbstract::getTypeOutName
static std::string getTypeOutName(void)
Definition: operator.hh:829
dynamicgraph::sigtime_t
int64_t sigtime_t
dynamicgraph::sot::Diagonalizer::resize
void resize(const size_type &r, const size_type &c)
Definition: operator.hh:235
dynamicgraph::sot::VectorSelecter::setBounds
void setBounds(const size_type &m, const size_type &M)
Definition: operator.hh:83
dynamicgraph::sot::QuaternionToMatrix::operator()
void operator()(const VectorQuaternion &r, MatrixRotation &res)
Definition: operator.hh:488
dynamicgraph::sot::PoseRollPitchYawToPoseUTheta::operator()
void operator()(const dg::Vector &vect, dg::Vector &vectres)
Definition: operator.hh:393
dynamicgraph::sot::PoseUThetaToMatrixHomo
Definition: operator.hh:310
dynamicgraph::sot::QuaternionToRPY
Definition: operator.hh:479
dynamicgraph::sot::PoseRollPitchYawToPoseUTheta
Definition: operator.hh:392
dynamicgraph::sot::VectorMix::Base
VariadicOp< VectorMix > Base
Definition: operator.hh:860
dynamicgraph::sot::MatrixToUTheta::operator()
void operator()(const MatrixRotation &r, VectorUTheta &res)
Definition: operator.hh:501
dynamicgraph::sot::VariadicOpHeader::nameTypeOut
static std::string nameTypeOut(void)
Definition: operator.hh:840
dynamicgraph::sot::VectorUTheta
Eigen::AngleAxis< double > SOT_CORE_EXPORT VectorUTheta
Definition: matrix-geometry.hh:77
dynamicgraph::sot::BinaryOpHeader::Tout
TypeOut Tout
Definition: operator.hh:517
dynamicgraph::sot::MatrixComparison::equal
bool equal
Definition: operator.hh:776
dynamicgraph::sot::SE3VectorToMatrixHomo
Definition: operator.hh:323
dynamicgraph::sot::Normalize::getDocString
std::string getDocString() const
Definition: operator.hh:269
dynamicgraph::sot::Multiplier_FxE__E::operator()
void operator()(const F &f, const E &e, E &res) const
Definition: operator.hh:558
dynamicgraph::sot::VariadicOpHeader::Tin
TypeIn Tin
Definition: operator.hh:835
dynamicgraph::sot::VariadicOpHeader::initialize
void initialize(VariadicOp< Op > *, Entity::CommandMap_t &)
Definition: operator.hh:844
dynamicgraph::Entity::CommandMap_t
std::map< const std::string, command::Command * > CommandMap_t
Index
std::size_t Index
variadic-op.hh
dynamicgraph::sot::BinaryOpHeader::nameTypeOut
static std::string nameTypeOut(void)
Definition: operator.hh:524
dynamicgraph::sot::ConvolutionTemporal
Definition: operator.hh:664
x
x
docCommandVoid3
std::string docCommandVoid3(const std::string &doc, const std::string &type1, const std::string &type2, const std::string &type3)
dynamicgraph::sot::VectorStack::v1min
size_type v1min
Definition: operator.hh:600
dynamicgraph::sot::Substraction::operator()
void operator()(const T &v1, const T &v2, T &r) const
Definition: operator.hh:589
dynamicgraph::sot::MatrixSelector::setBoundsRow
void setBoundsRow(const size_type &m, const size_type &M)
Definition: operator.hh:154
dynamicgraph::sot::UnaryOpHeader::nameTypeOut
static std::string nameTypeOut(void)
Definition: operator.hh:45
dynamicgraph::sot::AdderVariadic::entity
Base * entity
Definition: operator.hh:911
dynamicgraph::sot::Diagonalizer::nbr
std::size_t nbr
Definition: operator.hh:234
dynamicgraph::sot::UThetaToQuaternion
Definition: operator.hh:506
M
M
dynamicgraph::sot::VectorSelecter::segments_t
std::vector< segment_t > segments_t
Definition: operator.hh:79
docDirectSetter
std::string docDirectSetter(const std::string &name, const std::string &type)
q
q
dynamicgraph::sot::HomoToMatrix::operator()
void operator()(const MatrixHomogeneous &M, dg::Matrix &res)
Definition: operator.hh:412
dynamicgraph::size_type
Matrix::Index size_type
dynamicgraph::sot::AdderVariadic::Base
VariadicOp< AdderVariadic > Base
Definition: operator.hh:909
dynamicgraph::sot::MatrixComparison::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:762
dynamicgraph::Vector
Eigen::VectorXd Vector
dynamicgraph::sot::Multiplier::operator()
void operator()(const std::vector< const T * > &vs, T &res) const
Definition: operator.hh:954
dynamicgraph::sot::Inverser::operator()
void operator()(const Tin &m, Tout &res) const
Definition: operator.hh:261
dynamicgraph::sot::VectorStack::selec2
void selec2(const size_type &m, const size_type M)
Definition: operator.hh:622
dynamicgraph::sot::MatrixSelector::jmin
size_type jmin
Definition: operator.hh:152
dynamicgraph::sot::PoseUThetaToMatrixHomo::operator()
void operator()(const dg::Vector &v, MatrixHomogeneous &res)
Definition: operator.hh:312
toRotationMatrix
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
a
Vec3f a
dynamicgraph::sot::ConvolutionTemporal::operator()
void operator()(const dynamicgraph::Vector &v1, const dynamicgraph::Matrix &m2, dynamicgraph::Vector &res)
Definition: operator.hh:690
makeCommandVoid2
CommandVoid2< E, T1, T2 > * makeCommandVoid2(E &entity, boost::function< void(const T1 &, const T2 &)> function, const std::string &docString)
dynamicgraph::sot::WeightedAdder::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:795
docCommandVoid2
std::string docCommandVoid2(const std::string &doc, const std::string &type1, const std::string &type2)
dynamicgraph::sot::Multiplier::setIdentity
void setIdentity(T &res) const
Definition: operator.hh:963
dynamicgraph::sot::UnaryOpHeader::Tin
TypeIn Tin
Definition: operator.hh:40
dynamicgraph::sot::MatrixTwist
Eigen::Matrix< double, 6, 6 > SOT_CORE_EXPORT MatrixTwist
Definition: matrix-geometry.hh:82
linear-algebra.h
H
def H
dynamicgraph::sot::VectorMix::idxs
segments_t idxs
Definition: operator.hh:869
dynamicgraph::sot::Composer
Definition: operator.hh:652
dynamicgraph::sot::VectorSelecter::addBounds
void addBounds(const size_type &m, const size_type &M)
Definition: operator.hh:87
dynamicgraph::sot::VectorComponent::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:121
docDirectGetter
std::string docDirectGetter(const std::string &name, const std::string &type)
dynamicgraph::sot::MatrixComparison::operator()
void operator()(const T1 &a, const T2 &b, bool &res) const
Definition: operator.hh:729
dynamicgraph::sot::VectorMix::segments_t
std::vector< segment_t > segments_t
Definition: operator.hh:867
dynamicgraph::sot::Multiplier::initialize
void initialize(Base *ent, Entity::CommandMap_t &)
Definition: operator.hh:965
dynamicgraph::sot::UnaryOpHeader::Tout
TypeOut Tout
Definition: operator.hh:41
matrix-geometry.hh
dynamicgraph::sot::InverserRotation
Definition: operator.hh:278
dynamicgraph::sot::Inverser
Definition: operator.hh:258
dynamicgraph::sot::BinaryOpHeader::Tin2
TypeIn2 Tin2
Definition: operator.hh:516
dynamicgraph::sot::MatrixToQuaternion::operator()
void operator()(const MatrixRotation &r, VectorQuaternion &res)
Definition: operator.hh:495
dynamicgraph::sot::VectorSelecter::operator()
void operator()(const Tin &m, Vector &res) const
Definition: operator.hh:65
dynamicgraph::sot::VectorMix::operator()
void operator()(const std::vector< const Vector * > &vs, Vector &res) const
Definition: operator.hh:870
dynamicgraph::sot::Multiplier
Definition: operator.hh:951
dynamicgraph::sot::HomoToTwist
Definition: operator.hh:424
dynamicgraph::sot::QuaternionToMatrix
Definition: operator.hh:486
dynamicgraph::sot::AdderVariadic::coeffs
Vector coeffs
Definition: operator.hh:912
dynamicgraph::sot::Diagonalizer::operator()
void operator()(const dg::Vector &r, dg::Matrix &res)
Definition: operator.hh:228
dynamicgraph::sot::MatrixToRPY::operator()
void operator()(const MatrixRotation &r, VectorRollPitchYaw &res)
Definition: operator.hh:464
dynamicgraph::sot::MatrixComparison::getDocString
std::string getDocString() const
Definition: operator.hh:739
dynamicgraph::sot::Substraction
Definition: operator.hh:588
dynamicgraph::sot::VectorSelecter::segment_t
std::pair< Vector::Index, Vector::Index > segment_t
Definition: operator.hh:78
dynamicgraph::sot::VariadicOpHeader::updateSignalNumber
void updateSignalNumber(const size_type &)
Definition: operator.hh:845
dynamicgraph::sot::PoseRollPitchYawToMatrixHomo::operator()
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres)
Definition: operator.hh:376
dynamicgraph::sot::Multiplier_FxE__E
Definition: operator.hh:557
dynamicgraph::sot::VectorStack::selec1
void selec1(const size_type &m, const size_type M)
Definition: operator.hh:618
v
v
dynamicgraph::sot::BoolOp
Definition: operator.hh:997
dynamicgraph::sot::ConvolutionTemporal::convolution
void convolution(const MemoryType &f1, const dynamicgraph::Matrix &f2, dynamicgraph::Vector &res)
Definition: operator.hh:670
dynamicgraph::sot::MatrixRotation
Eigen::Matrix< double, 3, 3 > SOT_CORE_EXPORT MatrixRotation
Definition: matrix-geometry.hh:76
dynamicgraph::sot::MatrixHomoToPose::operator()
void operator()(const MatrixHomogeneous &M, Vector &res)
Definition: operator.hh:448
dynamicgraph::sot::VariadicOp
Definition: variadic-op.hh:139
dynamicgraph::sot::AdderVariadic
Definition: operator.hh:908
dynamicgraph::sot::MatrixColumnSelector::setBoundsRow
void setBoundsRow(const size_type &m, const size_type &M)
Definition: operator.hh:197
dynamicgraph::sot::BinaryOpHeader::nameTypeIn1
static std::string nameTypeIn1(void)
Definition: operator.hh:518
dynamicgraph::sot::MatrixTranspose
Definition: operator.hh:222
makeDirectSetter
DirectSetter< E, T > * makeDirectSetter(E &entity, T *ptr, const std::string &docString)
dynamicgraph::sot::MatrixComparison::MatrixComparison
MatrixComparison()
Definition: operator.hh:761
dynamicgraph::sot::ConvolutionTemporal::MemoryType
std::deque< dynamicgraph::Vector > MemoryType
Definition: operator.hh:667
dynamicgraph::sot::VariadicAbstract::addSignal
std::size_t addSignal()
Definition: variadic-op.hh:63
dynamicgraph::sot::AdderVariadic::getDocString
std::string getDocString() const
Definition: operator.hh:936
t
Transform3f t
dynamicgraph::sot::MatrixToHomo
Definition: operator.hh:417
dynamicgraph::sot::VariadicOpHeader::getDocString
std::string getDocString() const
Definition: operator.hh:846
sig
Signal< dynamicgraph::Matrix, sigtime_t > sig("matrix")
all-commands.h
dynamicgraph::sot::UnaryOpHeader::nameTypeIn
static std::string nameTypeIn(void)
Definition: operator.hh:42
dynamicgraph::sot::TypeNameHelper::typeName
static std::string typeName()
Definition: type-name-helper.hh:21
dynamicgraph::sot::Multiplier_matrix_vector
Multiplier_FxE__E< dynamicgraph::Matrix, dynamicgraph::Vector > Multiplier_matrix_vector
Definition: operator.hh:580
dynamicgraph::sot::RPYToMatrix::operator()
void operator()(const VectorRollPitchYaw &r, MatrixRotation &res)
Definition: operator.hh:455
dynamicgraph::sot::MatrixHomoToPose
Definition: operator.hh:447
ADD_COMMAND
#define ADD_COMMAND(name, def)
Definition: operator.hh:34
dynamicgraph::sot::InverserQuaternion::operator()
void operator()(const Tin &m, Tout &res) const
Definition: operator.hh:284
dynamicgraph::sot::MatrixHomoToPoseRollPitchYaw
Definition: operator.hh:362
dynamicgraph::sot::BinaryOpHeader::getDocString
std::string getDocString() const
Definition: operator.hh:528
dynamicgraph::sot::VectorMix
Definition: operator.hh:858
dynamicgraph::sot::MatrixHomoToPoseUTheta::operator()
void operator()(const MatrixHomogeneous &M, dg::Vector &res)
Definition: operator.hh:293
dynamicgraph::sot::MatrixHomoToPoseUTheta
Definition: operator.hh:291
dynamicgraph::sot::MatrixSelector::addSpecificCommands
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
Definition: operator.hh:163
dynamicgraph::sot::AdderVariadic::setCoeffs
void setCoeffs(const Vector &c)
Definition: operator.hh:922
dynamicgraph::sot::SkewSymToVector
Definition: operator.hh:301
dynamicgraph::sot::MatrixToUTheta
Definition: operator.hh:500
dynamicgraph::sot::WeightedAdder::operator()
void operator()(const T &v1, const T &v2, T &res) const
Definition: operator.hh:789
n
Vec3f n
dynamicgraph::sot::VectorComponent::getDocString
std::string getDocString() const
Definition: operator.hh:131
dynamicgraph::sot::MatrixColumnSelector::imin
size_type imin
Definition: operator.hh:194
dynamicgraph::command::makeCommandVoid1
CommandVoid1< E, T > * makeCommandVoid1(E &entity, boost::function< void(const T &)> function, const std::string &docString)
dynamicgraph::sot::SkewSymToVector::operator()
void operator()(const Matrix &M, Vector &res)
Definition: operator.hh:302
dynamicgraph::sot::VariadicOpHeader::nameTypeIn
static std::string nameTypeIn(void)
Definition: operator.hh:837
dynamicgraph::sot::BinaryOpHeader
Definition: operator.hh:514
dynamicgraph::sot::MatrixHomoToPoseRollPitchYaw::operator()
void operator()(const MatrixHomogeneous &M, dg::Vector &res)
Definition: operator.hh:364
dynamicgraph::sot::HomoToRotation::operator()
void operator()(const MatrixHomogeneous &M, MatrixRotation &res)
Definition: operator.hh:442
dynamicgraph::sot::VariadicAbstract::getSignalNumber
size_type getSignalNumber() const
Definition: variadic-op.hh:109
dynamicgraph::sot::VectorComponent::setIndex
void setIndex(const size_type &m)
Definition: operator.hh:119
dynamicgraph::sot::VectorMix::segment_t::size
Vector::Index size
Definition: operator.hh:862
sotDEBUG
#define sotDEBUG(level)
Definition: debug.hh:168
dynamicgraph::sot::SE3VectorToMatrixHomo::operator()
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres)
Definition: operator.hh:325
dynamicgraph::sot::MatrixColumnSelector::operator()
void operator()(const Tin &m, Tout &res) const
Definition: operator.hh:186


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Tue Oct 24 2023 02:26:31