sot-dynamic-pinocchio.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2016,
3  * François Bleibel,
4  * Olivier Stasse,
5  *
6  * CNRS/AIST
7  *
8  */
11 
12 #include <boost/filesystem.hpp>
13 #include <boost/format.hpp>
14 #include <boost/version.hpp>
15 #include <pinocchio/algorithm/center-of-mass.hpp>
16 #include <pinocchio/algorithm/centroidal.hpp>
17 #include <pinocchio/algorithm/crba.hpp>
18 #include <pinocchio/algorithm/jacobian.hpp>
19 #include <pinocchio/algorithm/kinematics.hpp>
20 #include <pinocchio/fwd.hpp>
21 #include <pinocchio/multibody/model.hpp>
22 #include <pinocchio/spatial/motion.hpp>
23 #include <sot/core/debug.hh>
24 
25 #include "../src/dynamic-command.h"
26 
27 using namespace dynamicgraph::sot;
28 using namespace dynamicgraph;
29 
30 const std::string dg::sot::DynamicPinocchio::CLASS_NAME = "DynamicPinocchio";
31 
33  : Entity(name),
34  m_model(NULL),
35  m_data()
36 
37  ,
38  jointPositionSIN(
39  NULL, "sotDynamicPinocchio(" + name + ")::input(vector)::position"),
40  freeFlyerPositionSIN(
41  NULL, "sotDynamicPinocchio(" + name + ")::input(vector)::ffposition"),
42  jointVelocitySIN(
43  NULL, "sotDynamicPinocchio(" + name + ")::input(vector)::velocity"),
44  freeFlyerVelocitySIN(
45  NULL, "sotDynamicPinocchio(" + name + ")::input(vector)::ffvelocity"),
46  jointAccelerationSIN(NULL, "sotDynamicPinocchio(" + name +
47  ")::input(vector)::acceleration"),
48  freeFlyerAccelerationSIN(NULL, "sotDynamicPinocchio(" + name +
49  ")::input(vector)::ffacceleration")
50 
51  ,
52  pinocchioPosSINTERN(
53  boost::bind(&DynamicPinocchio::getPinocchioPos, this, _1, _2),
54  jointPositionSIN << freeFlyerPositionSIN,
55  "sotDynamicPinocchio(" + name + ")::intern(dummy)::pinocchioPos"),
56  pinocchioVelSINTERN(
57  boost::bind(&DynamicPinocchio::getPinocchioVel, this, _1, _2),
58  jointVelocitySIN << freeFlyerVelocitySIN,
59  "sotDynamicPinocchio(" + name + ")::intern(dummy)::pinocchioVel"),
60  pinocchioAccSINTERN(
61  boost::bind(&DynamicPinocchio::getPinocchioAcc, this, _1, _2),
62  jointAccelerationSIN << freeFlyerAccelerationSIN,
63  "sotDynamicPinocchio(" + name + ")::intern(dummy)::pinocchioAcc")
64 
65  ,
66  newtonEulerSINTERN(
67  boost::bind(&DynamicPinocchio::computeNewtonEuler, this, _1, _2),
68  pinocchioPosSINTERN << pinocchioVelSINTERN << pinocchioAccSINTERN,
69  "sotDynamicPinocchio(" + name + ")::intern(dummy)::newtoneuler"),
70  jacobiansSINTERN(
71  boost::bind(&DynamicPinocchio::computeJacobians, this, _1, _2),
72  pinocchioPosSINTERN,
73  "sotDynamicPinocchio(" + name + ")::intern(dummy)::computeJacobians"),
74  forwardKinematicsSINTERN(
75  boost::bind(&DynamicPinocchio::computeForwardKinematics, this, _1,
76  _2),
77  pinocchioPosSINTERN << pinocchioVelSINTERN << pinocchioAccSINTERN,
78  "sotDynamicPinocchio(" + name +
79  ")::intern(dummy)::computeForwardKinematics"),
80  ccrbaSINTERN(
81  boost::bind(&DynamicPinocchio::computeCcrba, this, _1, _2),
82  pinocchioPosSINTERN << pinocchioVelSINTERN,
83  "sotDynamicPinocchio(" + name + ")::intern(dummy)::computeCcrba"),
84  zmpSOUT(boost::bind(&DynamicPinocchio::computeZmp, this, _1, _2),
85  newtonEulerSINTERN,
86  "sotDynamicPinocchio(" + name + ")::output(vector)::zmp"),
87  JcomSOUT(boost::bind(&DynamicPinocchio::computeJcom, this, _1, _2),
88  pinocchioPosSINTERN,
89  "sotDynamicPinocchio(" + name + ")::output(matrix)::Jcom"),
90  comSOUT(boost::bind(&DynamicPinocchio::computeCom, this, _1, _2),
91  forwardKinematicsSINTERN,
92  "sotDynamicPinocchio(" + name + ")::output(vector)::com"),
93  inertiaSOUT(boost::bind(&DynamicPinocchio::computeInertia, this, _1, _2),
94  pinocchioPosSINTERN,
95  "sotDynamicPinocchio(" + name + ")::output(matrix)::inertia"),
96  footHeightSOUT(
97  boost::bind(&DynamicPinocchio::computeFootHeight, this, _1, _2),
98  pinocchioPosSINTERN,
99  "sotDynamicPinocchio(" + name + ")::output(double)::footHeight"),
100  upperJlSOUT(
101  boost::bind(&DynamicPinocchio::getUpperPositionLimits, this, _1, _2),
102  sotNOSIGNAL,
103  "sotDynamicPinocchio(" + name + ")::output(vector)::upperJl")
104 
105  ,
106  lowerJlSOUT(
107  boost::bind(&DynamicPinocchio::getLowerPositionLimits, this, _1, _2),
108  sotNOSIGNAL,
109  "sotDynamicPinocchio(" + name + ")::output(vector)::lowerJl")
110 
111  ,
112  upperVlSOUT(
113  boost::bind(&DynamicPinocchio::getUpperVelocityLimits, this, _1, _2),
114  sotNOSIGNAL,
115  "sotDynamicPinocchio(" + name + ")::output(vector)::upperVl")
116 
117  ,
118  upperTlSOUT(
119  boost::bind(&DynamicPinocchio::getMaxEffortLimits, this, _1, _2),
120  sotNOSIGNAL,
121  "sotDynamicPinocchio(" + name + ")::output(vector)::upperTl")
122 
123  ,
124  inertiaRotorSOUT("sotDynamicPinocchio(" + name +
125  ")::output(matrix)::inertiaRotor"),
126  gearRatioSOUT("sotDynamicPinocchio(" + name +
127  ")::output(matrix)::gearRatio"),
128  inertiaRealSOUT(
129  boost::bind(&DynamicPinocchio::computeInertiaReal, this, _1, _2),
130  inertiaSOUT << gearRatioSOUT << inertiaRotorSOUT,
131  "sotDynamicPinocchio(" + name + ")::output(matrix)::inertiaReal"),
132  MomentaSOUT(boost::bind(&DynamicPinocchio::computeMomenta, this, _1, _2),
133  ccrbaSINTERN,
134  "sotDynamicPinocchio(" + name + ")::output(vector)::momenta"),
135  AngularMomentumSOUT(
136  boost::bind(&DynamicPinocchio::computeAngularMomentum, this, _1, _2),
137  ccrbaSINTERN,
138  "sotDynamicPinocchio(" + name + ")::output(vector)::angularmomentum"),
139  dynamicDriftSOUT(
140  boost::bind(&DynamicPinocchio::computeTorqueDrift, this, _1, _2),
141  newtonEulerSINTERN,
142  "sotDynamicPinocchio(" + name + ")::output(vector)::dynamicDrift") {
143  sotDEBUGIN(5);
144 
145  // TODO-------------------------------------------
146 
147  // if( build ) buildModel();
148  // firstSINTERN.setDependencyType(TimeDependency<int>::BOOL_DEPENDENT);
149  // DEBUG: Why =0? should be function. firstSINTERN.setConstant(0);
150  // endTODO--------------------------------------------
151 
173 
174  //
175  // Commands
176  //
177  std::string docstring;
178  // setFiles
179 
180  docstring =
181  "\n"
182  " Display the current robot configuration.\n"
183  "\n"
184  " Input:\n"
185  " - none \n"
186  "\n";
187  addCommand("displayModel", new command::DisplayModel(*this, docstring));
188  docstring =
189  " \n"
190  " Get the dimension of the robot configuration.\n"
191  " \n"
192  " Return:\n"
193  " an unsigned int: the dimension.\n"
194  " \n";
195  addCommand("getDimension", new command::GetDimension(*this, docstring));
196 
197  {
198  using namespace ::dg::command;
199  // CreateOpPoint
200  // TODO add operational joints
201  docstring =
202  " \n"
203  " Create an operational point attached to a robot joint local "
204  "frame.\n"
205  " \n"
206  " Input: \n"
207  " - a string: name of the operational point,\n"
208  " - a string: name the joint, or among (gaze, left-ankle, right "
209  "ankle\n"
210  " , left-wrist, right-wrist, waist, chest).\n"
211  "\n";
212  addCommand(
213  "createOpPoint",
215  docstring));
216 
217  docstring = docCommandVoid2(
218  "Create a jacobian (world frame) signal only for one joint.",
219  "string (signal name)", "string (joint name)");
220  addCommand("createJacobian",
223  docstring));
224 
225  docstring = docCommandVoid2(
226  "Create a jacobian (endeff frame) signal only for one joint.",
227  "string (signal name)", "string (joint name)");
228  addCommand(
229  "createJacobianEndEff",
230  makeCommandVoid2(*this,
232  docstring));
233 
234  docstring = docCommandVoid2(
235  "Create a jacobian (endeff frame) signal only for one joint. "
236  "The returned jacobian is placed at the joint position, but oriented "
237  "with the world axis.",
238  "string (signal name)", "string (joint name)");
239  addCommand(
240  "createJacobianEndEffWorld",
243  docstring));
244 
245  docstring = docCommandVoid2(
246  "Create a position (matrix homo) signal only for one joint.",
247  "string (signal name)", "string (joint name)");
248  addCommand(
249  "createPosition",
251  docstring));
252 
253  docstring =
254  docCommandVoid2("Create a velocity (vector) signal only for one joint.",
255  "string (signal name)", "string (joint name)");
256  addCommand(
257  "createVelocity",
259  docstring));
260 
261  docstring = docCommandVoid2(
262  "Create an acceleration (vector) signal only for one joint.",
263  "string (signal name)", "string (joint name)");
264  addCommand(
265  "createAcceleration",
267  docstring));
268  docstring =
269  "\n"
270  " Return robot joint names.\n\n";
271  addCommand("getJointNames", new command::GetJointNames(*this, docstring));
272  }
273 
274  sphericalJoints.clear();
275 
276  sotDEBUG(10) << "Dynamic class_name address" << &CLASS_NAME << std::endl;
277  sotDEBUGOUT(5);
278 }
279 
281  sotDEBUGIN(15);
282  // TODO currently, m_model and m_data are pointers owned by the Python
283  // interpreter so we should not delete them. I (Joseph Mirabel) think it would
284  // be wiser to make them belong to this class but I do not know the impact it
285  // has. if (0!=m_data ) { delete m_data ; m_data =NULL; } if (0!=m_model) {
286  // delete m_model; m_model=NULL; }
287 
288  for (std::list<SignalBase<sigtime_t>*>::iterator iter =
289  genericSignalRefs.begin();
290  iter != genericSignalRefs.end(); ++iter) {
291  SignalBase<sigtime_t>* sigPtr = *iter;
292  delete sigPtr;
293  }
294  sotDEBUGOUT(15);
295 }
296 
298  this->m_model = modelPtr;
299 
300  if (this->m_model->nq > m_model->nv) {
301  if (pinocchio::nv(this->m_model->joints[1]) == 6)
302  sphericalJoints.push_back(3); // FreeFlyer Orientation
303 
304  for (int i = 1; i < this->m_model->njoints; i++) // 0: universe
305  if (pinocchio::nq(this->m_model->joints[i]) == 4) // Spherical Joint Only
306  sphericalJoints.push_back(pinocchio::idx_v(this->m_model->joints[i]));
307  }
308 
309  createData();
310 }
311 
313  m_data.reset(new pinocchio::Data(*m_model));
314 }
315 
316 /*--------------------------------GETTERS-------------------------------------------*/
317 
319  const sigtime_t&) const {
320  sotDEBUGIN(15);
321  assert(m_model);
322 
323  res.resize(m_model->nv);
324  if (!sphericalJoints.empty()) {
325  int fillingIndex = 0; // SoTValue
326  int origIndex = 0; // PinocchioValue
327  for (std::vector<int>::const_iterator it = sphericalJoints.begin();
328  it < sphericalJoints.end(); it++) {
329  if (*it - fillingIndex > 0) {
330  res.segment(fillingIndex, *it - fillingIndex) =
331  m_model->lowerPositionLimit.segment(origIndex, *it - fillingIndex);
332 
333  // Don't Change this order
334  origIndex += *it - fillingIndex;
335  fillingIndex += *it - fillingIndex;
336  }
337  // Found a Spherical Joint.
338  // Assuming that spherical joint limits are unset
339  // Version C++11
340  // res(fillingIndex) = std::numeric_limits<double>::lowest();
341  // res(fillingIndex + 1) = std::numeric_limits<double>::lowest();
342  // res(fillingIndex + 2) = std::numeric_limits<double>::lowest();
343  // For now use C++98
344  res(fillingIndex) = -std::numeric_limits<double>::max();
345  res(fillingIndex + 1) = -std::numeric_limits<double>::max();
346  res(fillingIndex + 2) = -std::numeric_limits<double>::max();
347 
348  fillingIndex += 3;
349  origIndex += 4;
350  }
351 
352  assert(m_model->nv - fillingIndex == m_model->nq - origIndex);
353  if (m_model->nv > fillingIndex)
354  res.segment(fillingIndex, m_model->nv - fillingIndex) =
355  m_model->lowerPositionLimit.segment(origIndex,
356  m_model->nv - fillingIndex);
357  } else {
359  }
360  sotDEBUG(15) << "lowerLimit (" << res << ")=" << std::endl;
361  sotDEBUGOUT(15);
362  return res;
363 }
364 
366  const sigtime_t&) const {
367  sotDEBUGIN(15);
368  assert(m_model);
369 
370  res.resize(m_model->nv);
371  if (!sphericalJoints.empty()) {
372  int fillingIndex = 0; // SoTValue
373  int origIndex = 0; // PinocchioValue
374  for (std::vector<int>::const_iterator it = sphericalJoints.begin();
375  it < sphericalJoints.end(); it++) {
376  if (*it - fillingIndex > 0) {
377  res.segment(fillingIndex, *it - fillingIndex) =
378  m_model->upperPositionLimit.segment(origIndex, *it - fillingIndex);
379 
380  // Don't Change this order
381  origIndex += *it - fillingIndex;
382  fillingIndex += *it - fillingIndex;
383  }
384  // Found a Spherical Joint.
385  // Assuming that spherical joint limits are unset
386  res(fillingIndex) = std::numeric_limits<double>::max();
387  res(fillingIndex + 1) = std::numeric_limits<double>::max();
388  res(fillingIndex + 2) = std::numeric_limits<double>::max();
389  fillingIndex += 3;
390  origIndex += 4;
391  }
392  assert(m_model->nv - fillingIndex == m_model->nq - origIndex);
393  if (m_model->nv > fillingIndex)
394  res.segment(fillingIndex, m_model->nv - fillingIndex) =
395  m_model->upperPositionLimit.segment(origIndex,
396  m_model->nv - fillingIndex);
397  } else {
399  }
400  sotDEBUG(15) << "upperLimit (" << res << ")=" << std::endl;
401  sotDEBUGOUT(15);
402  return res;
403 }
404 
406  const sigtime_t&) const {
407  sotDEBUGIN(15);
408  assert(m_model);
409 
410  res.resize(m_model->nv);
412 
413  sotDEBUG(15) << "upperVelocityLimit (" << res << ")=" << std::endl;
414  sotDEBUGOUT(15);
415  return res;
416 }
417 
419  const sigtime_t&) const {
420  sotDEBUGIN(15);
421  assert(m_model);
422 
423  res.resize(m_model->nv);
425 
426  sotDEBUGOUT(15);
427  return res;
428 }
429 
430 /* ---------------- INTERNAL ------------------------------------------------ */
432  const sigtime_t& time) {
433  sotDEBUGIN(15);
434  dg::Vector qJoints = jointPositionSIN.access(time);
435  if (!sphericalJoints.empty()) {
436  if (freeFlyerPositionSIN) {
438  qJoints.head<6>() = qFF; // Overwrite qJoints ff with ffposition value
439  assert(sphericalJoints[0] == 3); // FreeFlyer should ideally be present.
440  }
441  q.resize(qJoints.size() + sphericalJoints.size());
442  int fillingIndex = 0;
443  int origIndex = 0;
444  for (std::vector<int>::const_iterator it = sphericalJoints.begin();
445  it < sphericalJoints.end(); it++) {
446  if (*it - origIndex > 0) {
447  q.segment(fillingIndex, *it - origIndex) =
448  qJoints.segment(origIndex, *it - origIndex);
449  fillingIndex += *it - origIndex;
450  origIndex += *it - origIndex;
451  }
452  assert(*it == origIndex);
453  Eigen::Quaternion<double> temp =
454  Eigen::AngleAxisd(qJoints(origIndex + 2), Eigen::Vector3d::UnitZ()) *
455  Eigen::AngleAxisd(qJoints(origIndex + 1), Eigen::Vector3d::UnitY()) *
456  Eigen::AngleAxisd(qJoints(origIndex), Eigen::Vector3d::UnitX());
457  q(fillingIndex) = temp.x();
458  q(fillingIndex + 1) = temp.y();
459  q(fillingIndex + 2) = temp.z();
460  q(fillingIndex + 3) = temp.w();
461  fillingIndex += 4;
462  origIndex += 3;
463  }
464  if (qJoints.size() > origIndex)
465  q.segment(fillingIndex, qJoints.size() - origIndex) =
466  qJoints.tail(qJoints.size() - origIndex);
467  } else {
468  q.resize(qJoints.size());
469  q = qJoints;
470  }
471 
472  sotDEBUG(15) << "Position out" << q << std::endl;
473  sotDEBUGOUT(15);
474  return q;
475 }
476 
478  const sigtime_t& time) {
479  const Eigen::VectorXd vJoints = jointVelocitySIN.access(time);
480  if (freeFlyerVelocitySIN) {
481  const Eigen::VectorXd vFF = freeFlyerVelocitySIN.access(time);
482  if (v.size() != vJoints.size() + vFF.size())
483  v.resize(vJoints.size() + vFF.size());
484  v << vFF, vJoints;
485  return v;
486  } else {
487  v = vJoints;
488  return v;
489  }
490 }
491 
493  const sigtime_t& time) {
494  const Eigen::VectorXd aJoints = jointAccelerationSIN.access(time);
496  const Eigen::VectorXd aFF = freeFlyerAccelerationSIN.access(time);
497  if (a.size() != aJoints.size() + aFF.size())
498  a.resize(aJoints.size() + aFF.size());
499  a << aFF, aJoints;
500  return a;
501  } else {
502  a = aJoints;
503  return a;
504  }
505 }
506 
507 /* --- SIGNAL ACTIVATION ---------------------------------------------------- */
509 DynamicPinocchio::createJacobianSignal(const std::string& signame,
510  const std::string& jointName) {
511  sotDEBUGIN(15);
512  assert(m_model);
514  if (m_model->existFrame(jointName)) {
515  long int frameId = m_model->getFrameId(jointName);
517  boost::bind(&DynamicPinocchio::computeGenericJacobian, this, true,
518  frameId, _1, _2),
520  "sotDynamicPinocchio(" + name + ")::output(matrix)::" + signame);
521  } else if (m_model->existJointName(jointName)) {
522  long int jointId = m_model->getJointId(jointName);
524  boost::bind(&DynamicPinocchio::computeGenericJacobian, this, false,
525  jointId, _1, _2),
527  "sotDynamicPinocchio(" + name + ")::output(matrix)::" + signame);
528  } else
531  "Robot has no joint corresponding to " + jointName);
532 
533  genericSignalRefs.push_back(sig);
535  sotDEBUGOUT(15);
536  return *sig;
537 }
538 
541  const std::string& jointName,
542  const bool isLocal) {
543  sotDEBUGIN(15);
544  assert(m_model);
546 
547  if (m_model->existFrame(jointName)) {
548  long int frameId = m_model->getFrameId(jointName);
550  boost::bind(&DynamicPinocchio::computeGenericEndeffJacobian, this, true,
551  isLocal, frameId, _1, _2),
553  "sotDynamicPinocchio(" + name + ")::output(matrix)::" + signame);
554  } else if (m_model->existJointName(jointName)) {
555  long int jointId = m_model->getJointId(jointName);
558  false, isLocal, jointId, _1, _2),
560  "sotDynamicPinocchio(" + name + ")::output(matrix)::" + signame);
561  } else
564  "Robot has no joint corresponding to " + jointName);
565  genericSignalRefs.push_back(sig);
567  sotDEBUGOUT(15);
568  return *sig;
569 }
570 
572 DynamicPinocchio::createPositionSignal(const std::string& signame,
573  const std::string& jointName) {
574  sotDEBUGIN(15);
575  assert(m_model);
577  if (m_model->existFrame(jointName)) {
578  long int frameId = m_model->getFrameId(jointName);
580  boost::bind(&DynamicPinocchio::computeGenericPosition, this, true,
581  frameId, _1, _2),
583  "sotDynamicPinocchio(" + name + ")::output(matrixHomo)::" + signame);
584  } else if (m_model->existJointName(jointName)) {
585  long int jointId = m_model->getJointId(jointName);
587  boost::bind(&DynamicPinocchio::computeGenericPosition, this, false,
588  jointId, _1, _2),
590  "sotDynamicPinocchio(" + name + ")::output(matrixHomo)::" + signame);
591  } else
594  "Robot has no joint corresponding to " + jointName);
595 
596  genericSignalRefs.push_back(sig);
598  sotDEBUGOUT(15);
599  return *sig;
600 }
601 
603 DynamicPinocchio::createVelocitySignal(const std::string& signame,
604  const std::string& jointName) {
605  sotDEBUGIN(15);
606  assert(m_model);
607  long int jointId = m_model->getJointId(jointName);
608 
611  boost::bind(&DynamicPinocchio::computeGenericVelocity, this, jointId,
612  _1, _2),
614  "sotDynamicPinocchio(" + name + ")::output(dg::Vector)::" + signame);
615  genericSignalRefs.push_back(sig);
617 
618  sotDEBUGOUT(15);
619  return *sig;
620 }
621 
624  const std::string& jointName) {
625  sotDEBUGIN(15);
626  assert(m_model);
627  long int jointId = m_model->getJointId(jointName);
631  jointId, _1, _2),
633  "sotDynamicPinocchio(" + name + ")::output(dg::Vector)::" + signame);
634 
635  genericSignalRefs.push_back(sig);
637 
638  sotDEBUGOUT(15);
639  return *sig;
640 }
641 
642 void DynamicPinocchio::destroyJacobianSignal(const std::string& signame) {
643  sotDEBUGIN(15);
644 
645  bool deletable = false;
647  for (std::list<SignalBase<sigtime_t>*>::iterator iter =
648  genericSignalRefs.begin();
649  iter != genericSignalRefs.end(); ++iter) {
650  if ((*iter) == sig) {
651  genericSignalRefs.erase(iter);
652  deletable = true;
653  break;
654  }
655  }
656 
657  if (!deletable) {
659  ExceptionDynamic::CANT_DESTROY_SIGNAL, "Cannot destroy signal",
660  " (while trying to remove generic jac. signal <%s>).", signame.c_str());
661  }
662  signalDeregistration(signame);
663  delete sig;
664 }
665 
666 void DynamicPinocchio::destroyPositionSignal(const std::string& signame) {
667  sotDEBUGIN(15);
668  bool deletable = false;
670  &positionsSOUT(signame);
671  for (std::list<SignalBase<sigtime_t>*>::iterator iter =
672  genericSignalRefs.begin();
673  iter != genericSignalRefs.end(); ++iter) {
674  if ((*iter) == sig) {
675  genericSignalRefs.erase(iter);
676  deletable = true;
677  break;
678  }
679  }
680 
681  if (!deletable) {
683  ExceptionDynamic::CANT_DESTROY_SIGNAL, "Cannot destroy signal",
684  " (while trying to remove generic pos. signal <%s>).", signame.c_str());
685  }
686 
687  signalDeregistration(signame);
688 
689  delete sig;
690 }
691 
692 void DynamicPinocchio::destroyVelocitySignal(const std::string& signame) {
693  sotDEBUGIN(15);
694  bool deletable = false;
696  for (std::list<SignalBase<sigtime_t>*>::iterator iter =
697  genericSignalRefs.begin();
698  iter != genericSignalRefs.end(); ++iter) {
699  if ((*iter) == sig) {
700  genericSignalRefs.erase(iter);
701  deletable = true;
702  break;
703  }
704  }
705 
706  if (!deletable) {
708  ExceptionDynamic::CANT_DESTROY_SIGNAL, "Cannot destroy signal",
709  " (while trying to remove generic pos. signal <%s>).", signame.c_str());
710  }
711 
712  signalDeregistration(signame);
713 
714  delete sig;
715 }
716 
717 void DynamicPinocchio::destroyAccelerationSignal(const std::string& signame) {
718  sotDEBUGIN(15);
719  bool deletable = false;
721  &accelerationsSOUT(signame);
722  for (std::list<SignalBase<sigtime_t>*>::iterator iter =
723  genericSignalRefs.begin();
724  iter != genericSignalRefs.end(); ++iter) {
725  if ((*iter) == sig) {
726  genericSignalRefs.erase(iter);
727  deletable = true;
728  break;
729  }
730  }
731 
732  if (!deletable) {
734  getName() + ":cannot destroy signal",
735  " (while trying to remove generic acc "
736  "signal <%s>).",
737  signame.c_str());
738  }
739 
740  signalDeregistration(signame);
741 
742  delete sig;
743 }
744 
745 /* --------------------- COMPUTE
746  * ------------------------------------------------- */
747 
749  const sigtime_t& time) {
750  // TODO: To be verified
751  sotDEBUGIN(25);
752  assert(m_data);
753  if (res.size() != 3) res.resize(3);
754  newtonEulerSINTERN(time);
755 
756  const pinocchio::Force& ftau = m_data->oMi[1].act(m_data->f[1]);
757  const pinocchio::Force::Vector3& tau = ftau.angular();
758  const pinocchio::Force::Vector3& f = ftau.linear();
759  res(0) = -tau[1] / f[2];
760  res(1) = tau[0] / f[2];
761  res(2) = 0;
762 
763  sotDEBUGOUT(25);
764 
765  return res;
766 }
767 
768 // In world coordinates
769 
770 // Updates the jacobian matrix in m_data
771 int& DynamicPinocchio::computeJacobians(int& dummy, const sigtime_t& time) {
772  sotDEBUGIN(25);
775  sotDEBUG(25) << "Jacobians updated" << std::endl;
776  sotDEBUGOUT(25);
777  return dummy;
778 }
780  const sigtime_t& time) {
781  sotDEBUGIN(25);
782  assert(m_model);
783  assert(m_data);
784  const Eigen::VectorXd& q = pinocchioPosSINTERN.access(time);
785  const Eigen::VectorXd& v = pinocchioVelSINTERN.access(time);
786  const Eigen::VectorXd& a = pinocchioAccSINTERN.access(time);
788  sotDEBUG(25) << "Kinematics updated" << std::endl;
789  sotDEBUGOUT(25);
790  return dummy;
791 }
792 
793 int& DynamicPinocchio::computeCcrba(int& dummy, const sigtime_t& time) {
794  sotDEBUGIN(25);
795  const Eigen::VectorXd& q = pinocchioPosSINTERN.access(time);
796  const Eigen::VectorXd& v = pinocchioVelSINTERN.access(time);
798  sotDEBUG(25) << "Inertia and Momentum updated" << std::endl;
799  sotDEBUGOUT(25);
800  return dummy;
801 }
802 
804  const int jointId,
805  dg::Matrix& res,
806  const sigtime_t& time) {
807  sotDEBUGIN(25);
808  assert(m_model);
809  assert(m_data);
810  if (res.rows() != 6 || res.cols() != m_model->nv)
811  res = Matrix::Zero(6, m_model->nv);
812  jacobiansSINTERN(time);
813 
815  isFrame ? m_model->frames[(pinocchio::JointIndex)jointId].parent
816  : (pinocchio::JointIndex)jointId;
817 
818  // Computes Jacobian in world coordinates.
820  sotDEBUGOUT(25);
821  return res;
822 }
823 
825  const bool isFrame, const bool isLocal, const int id, dg::Matrix& res,
826  const sigtime_t& time) {
827  sotDEBUGIN(25);
828  assert(m_model);
829  assert(m_data);
830  if (res.rows() != 6 || res.cols() != m_model->nv)
831  res = Matrix::Zero(6, m_model->nv);
832 
833  jacobiansSINTERN(time);
834 
837  bool changeFrame = !isLocal;
839 
840  // Computes Jacobian in end-eff coordinates.
841  if (isFrame) {
842  changeFrame = true;
843  fid = (pinocchio::FrameIndex)id;
844  const pinocchio::Frame& frame = m_model->frames[fid];
845  jid = frame.parent;
846 
847  M = frame.placement.inverse();
848 
849  if (!isLocal) { // Express the jacobian is world coordinate system.
850  // Need to compute frame placement for oMf.
852 
854  T.rotation() = m_data->oMf[fid].rotation();
855  T.translation().setZero();
856  M = T * M;
857  }
858  } else {
859  jid = (pinocchio::JointIndex)id;
860  if (!isLocal) { // Express the jacobian is world coordinate system.
861  M.rotation() = m_data->oMi[jid].rotation();
862  M.translation().setZero();
863  }
864  }
866 
867  if (changeFrame) pinocchio::motionSet::se3Action(M, res, res);
868 
869  sotDEBUGOUT(25);
870  return res;
871 }
872 
874  const bool isFrame, const int id, MatrixHomogeneous& res,
875  const sigtime_t& time) {
876  sotDEBUGIN(25);
878  if (isFrame) {
879  const pinocchio::Frame& frame = m_model->frames[id];
880  res.matrix() =
881  (m_data->oMi[frame.parent] * frame.placement).toHomogeneousMatrix();
882  } else {
883  res.matrix() = m_data->oMi[id].toHomogeneousMatrix();
884  }
885  sotDEBUG(25) << "For "
886  << (isFrame ? m_model->frames[id].name : m_model->names[id])
887  << " with id: " << id << " position is " << res << std::endl;
888  sotDEBUGOUT(25);
889  return res;
890 }
891 
893  dg::Vector& res,
894  const sigtime_t& time) {
895  sotDEBUGIN(25);
897  res.resize(6);
898  const pinocchio::Motion& aRV = m_data->v[jointId];
899  res << aRV.linear(), aRV.angular();
900  sotDEBUGOUT(25);
901  return res;
902 }
903 
905  const int jointId, dg::Vector& res, const sigtime_t& time) {
906  sotDEBUGIN(25);
908  res.resize(6);
909  const pinocchio::Motion& aRA = m_data->a[jointId];
910  res << aRA.linear(), aRA.angular();
911  sotDEBUGOUT(25);
912  return res;
913 }
914 
915 int& DynamicPinocchio::computeNewtonEuler(int& dummy, const sigtime_t& time) {
916  sotDEBUGIN(15);
917  assert(m_model);
918  assert(m_data);
919  const Eigen::VectorXd& q = pinocchioPosSINTERN.access(time);
920  const Eigen::VectorXd& v = pinocchioVelSINTERN.access(time);
921  const Eigen::VectorXd& a = pinocchioAccSINTERN.access(time);
923 
924  sotDEBUG(1) << "pos = " << q << std::endl;
925  sotDEBUG(1) << "vel = " << v << std::endl;
926  sotDEBUG(1) << "acc = " << a << std::endl;
927 
928  sotDEBUGOUT(15);
929  return dummy;
930 }
931 
933  const sigtime_t& time) {
934  sotDEBUGIN(25);
937  sotDEBUGOUT(25);
938  return Jcom;
939 }
940 
942  const sigtime_t& time) {
943  sotDEBUGIN(25);
944  if (JcomSOUT.needUpdate(time)) {
947  }
948  com = m_data->com[0];
949  sotDEBUGOUT(25);
950  return com;
951 }
952 
954  const sigtime_t& time) {
955  sotDEBUGIN(25);
956  const Eigen::VectorXd& q = pinocchioPosSINTERN.access(time);
958  res.triangularView<Eigen::StrictlyLower>() =
959  res.transpose().triangularView<Eigen::StrictlyLower>();
960  sotDEBUGOUT(25);
961  return res;
962 }
963 
965  const sigtime_t& time) {
966  sotDEBUGIN(25);
967 
968  const dg::Matrix& A = inertiaSOUT(time);
969  const dg::Vector& gearRatio = gearRatioSOUT(time);
971 
972  res = A;
973  for (int i = 0; i < gearRatio.size(); ++i)
974  res(i, i) += (gearRatio(i) * gearRatio(i) * inertiaRotor(i));
975 
976  sotDEBUGOUT(25);
977  return res;
978 }
979 
980 double& DynamicPinocchio::computeFootHeight(double& res, const sigtime_t&) {
981  // Ankle position in local foot frame
982  // TODO: Confirm that it is in the foot frame
983  sotDEBUGIN(25);
984  if (!m_model->existJointName("r_sole_joint")) {
986  "Robot has no joint corresponding to rigthFoot");
987  }
988  long int jointId = m_model->getJointId("r_sole_joint");
989  Eigen::Vector3d anklePosInLocalRefFrame = m_data->liMi[jointId].translation();
990  // TODO: positive or negative? Current output:negative
991  res = anklePosInLocalRefFrame(2);
992  sotDEBUGOUT(25);
993  return res;
994 }
995 
997  const sigtime_t& time) {
998  sotDEBUGIN(25);
999  newtonEulerSINTERN(time);
1000  tauDrift = m_data->tau;
1001  sotDEBUGOUT(25);
1002  return tauDrift;
1003 }
1004 
1006  const sigtime_t& time) {
1007  sotDEBUGIN(25);
1008  ccrbaSINTERN(time);
1009  if (Momenta.size() != 6) Momenta.resize(6);
1010 
1011  Momenta = m_data->hg.toVector_impl();
1012 
1013  sotDEBUGOUT(25) << "Momenta :" << Momenta;
1014  return Momenta;
1015 }
1016 
1018  const sigtime_t& time) {
1019  sotDEBUGIN(25);
1020  ccrbaSINTERN(time);
1021 
1022  if (Momenta.size() != 3) Momenta.resize(3);
1023  Momenta = m_data->hg.angular_impl();
1024 
1025  sotDEBUGOUT(25) << "AngularMomenta :" << Momenta;
1026  return Momenta;
1027 }
1028 
1029 /* ------------------------ SIGNAL
1030  * CASTING--------------------------------------- */
1031 
1033  const std::string& name) {
1035  try {
1037  dynamic_cast<dg::SignalTimeDependent<dg::Matrix, sigtime_t>&>(sigabs);
1038  return res;
1039  } catch (const std::bad_cast& e) {
1041  " (while getting signal <%s> of type matrix.",
1042  name.c_str());
1043  }
1044 }
1048  try {
1051  sigabs);
1052  return res;
1053  } catch (const std::bad_cast& e) {
1055  " (while getting signal <%s> of type matrixHomo.",
1056  name.c_str());
1057  }
1058 }
1059 
1063  try {
1065  dynamic_cast<dg::SignalTimeDependent<dg::Vector, sigtime_t>&>(sigabs);
1066  return res;
1067  } catch (const std::bad_cast& e) {
1069  " (while getting signal <%s> of type Vector.",
1070  name.c_str());
1071  }
1072 }
1073 
1077  try {
1079  dynamic_cast<dg::SignalTimeDependent<dg::Vector, sigtime_t>&>(sigabs);
1080  return res;
1081  } catch (const std::bad_cast& e) {
1083  " (while getting signal <%s> of type Vector.",
1084  name.c_str());
1085  }
1086 }
1087 
1088 /*-------------------------------------------------------------------------*/
1089 
1090 /*-------------------------------------------------------------------------*/
1091 
1092 /* --- PARAMS --------------------------------------------------------------- */
1093 
1094 // jointName is either a fixed-joint (pinocchio operational frame) or a
1095 // movable joint (pinocchio joint-variant).
1096 void DynamicPinocchio::cmd_createOpPointSignals(const std::string& opPointName,
1097  const std::string& jointName) {
1098  createEndeffJacobianSignal(std::string("J") + opPointName, jointName, true);
1099  createPositionSignal(opPointName, jointName);
1100 }
1102  const std::string& signalName, const std::string& jointName) {
1103  createJacobianSignal(signalName, jointName);
1104 }
1106  const std::string& signalName, const std::string& jointName) {
1107  createEndeffJacobianSignal(signalName, jointName, true);
1108 }
1109 
1111  const std::string& signalName, const std::string& jointName) {
1112  createEndeffJacobianSignal(signalName, jointName, false);
1113 }
1114 
1115 void DynamicPinocchio::cmd_createPositionSignal(const std::string& signalName,
1116  const std::string& jointName) {
1117  createPositionSignal(signalName, jointName);
1118 }
1119 void DynamicPinocchio::cmd_createVelocitySignal(const std::string& signalName,
1120  const std::string& jointName) {
1121  createVelocitySignal(signalName, jointName);
1122 }
1124  const std::string& signalName, const std::string& jointName) {
1125  createAccelerationSignal(signalName, jointName);
1126 }
pinocchio::jacobianCenterOfMass
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & jacobianCenterOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
pinocchio::WORLD
WORLD
pinocchio::FrameIndex
Index FrameIndex
pinocchio::FrameTpl::placement
SE3 placement
pinocchio::ModelTpl::names
std::vector< std::string > names
dynamicgraph::sot::DynamicPinocchio::computeCcrba
int & computeCcrba(int &dummy, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:793
dynamicgraph::sot::DynamicPinocchio::computeInertiaReal
dg::Matrix & computeInertiaReal(dg::Matrix &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:964
dynamicgraph::sot::DynamicPinocchio::ccrbaSINTERN
dg::SignalTimeDependent< Dummy, sigtime_t > ccrbaSINTERN
Definition: dynamic-pinocchio.h:135
dynamicgraph::sot::DynamicPinocchio::upperVlSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > upperVlSOUT
Definition: dynamic-pinocchio.h:159
pinocchio::ModelTpl::frames
FrameVector frames
pinocchio::DataTpl
dynamicgraph::SignalTimeDependent::access
const T & access(const Time &t1)
dynamicgraph::sot::DynamicPinocchio::sphericalJoints
std::vector< int > sphericalJoints
Definition: dynamic-pinocchio.h:267
dynamic-pinocchio.h
dynamicgraph::sot::DynamicPinocchio::computeGenericEndeffJacobian
dg::Matrix & computeGenericEndeffJacobian(const bool isFrame, const bool isLocal, const int jointId, dg::Matrix &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:824
SE3Tpl< Scalar, Options >::inverse
SE3Tpl inverse() const
dynamicgraph::sot::DynamicPinocchio::pinocchioAccSINTERN
dg::SignalTimeDependent< dg::Vector, sigtime_t > pinocchioAccSINTERN
Definition: dynamic-pinocchio.h:130
pinocchio::forwardKinematics
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
pinocchio::ModelTpl::existJointName
bool existJointName(const std::string &name) const
dynamicgraph::sot::MatrixHomogeneous
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
dynamicgraph::sot::DynamicPinocchio::computeJacobians
int & computeJacobians(int &dummy, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:771
dynamicgraph::sot::DynamicPinocchio::forwardKinematicsSINTERN
dg::SignalTimeDependent< Dummy, sigtime_t > forwardKinematicsSINTERN
Definition: dynamic-pinocchio.h:134
dynamicgraph::sot::ExceptionSignal
T
int T
parent
parent
dynamicgraph::sot::DynamicPinocchio::computeFootHeight
double & computeFootHeight(double &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:980
pinocchio::ModelTpl::lowerPositionLimit
ConfigVectorType lowerPositionLimit
dynamicgraph::sot::DynamicPinocchio::freeFlyerAccelerationSIN
dg::SignalPtr< dg::Vector, sigtime_t > freeFlyerAccelerationSIN
Definition: dynamic-pinocchio.h:126
pinocchio::idx_v
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
dynamicgraph
dynamicgraph::sot::ExceptionDynamic
pinocchio::nv
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
kineromeo.gearRatio
tuple gearRatio
Definition: kineromeo.py:94
id
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
SE3Tpl< double, 0 >
pinocchio::nq
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
i
int i
dynamicgraph::sot::DynamicPinocchio::jointVelocitySIN
dg::SignalPtr< dg::Vector, sigtime_t > jointVelocitySIN
Definition: dynamic-pinocchio.h:123
dynamicgraph::sot::DynamicPinocchio::getMaxEffortLimits
dg::Vector & getMaxEffortLimits(dg::Vector &res, const sigtime_t &) const
Get joint effort upper limits.
Definition: sot-dynamic-pinocchio.cpp:418
dynamicgraph::sot::DynamicPinocchio
This class provides an inverse dynamic model of the robot. More precisely it wraps the newton euler a...
Definition: dynamic-pinocchio.h:79
dynamicgraph::Entity
dynamicgraph::sot::DynamicPinocchio::m_model
pinocchio::Model * m_model
Definition: dynamic-pinocchio.h:89
dynamicgraph::sot::DynamicPinocchio::upperJlSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > upperJlSOUT
Definition: dynamic-pinocchio.h:157
dynamicgraph::sot::DynamicPinocchio::comSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > comSOUT
Definition: dynamic-pinocchio.h:144
dynamicgraph::sot::DynamicPinocchio::m_data
std::unique_ptr< pinocchio::Data > m_data
Definition: dynamic-pinocchio.h:90
dynamicgraph::sot::DynamicPinocchio::cmd_createPositionSignal
void cmd_createPositionSignal(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1115
dynamicgraph::sot::DynamicPinocchio::zmpSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > zmpSOUT
Definition: dynamic-pinocchio.h:142
dynamicgraph::sot::DynamicPinocchio::inertiaRealSOUT
dg::SignalTimeDependent< dg::Matrix, sigtime_t > inertiaRealSOUT
Definition: dynamic-pinocchio.h:164
dynamicgraph::sot::DynamicPinocchio::pinocchioPosSINTERN
dg::SignalTimeDependent< dg::Vector, sigtime_t > pinocchioPosSINTERN
Definition: dynamic-pinocchio.h:128
boost
pinocchio::ModelTpl::joints
JointModelVector joints
debug.hh
pinocchio::ModelTpl::existFrame
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
dynamicgraph::sot::DynamicPinocchio::jacobiansSOUT
dg::SignalTimeDependent< dg::Matrix, sigtime_t > & jacobiansSOUT(const std::string &name)
Definition: sot-dynamic-pinocchio.cpp:1032
dynamicgraph::Entity::name
std::string name
pinocchio::ccrba
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
dynamicgraph::sot::DynamicPinocchio::cmd_createJacobianEndEffectorSignal
void cmd_createJacobianEndEffectorSignal(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1105
dynamicgraph::sot::DynamicPinocchio::freeFlyerVelocitySIN
dg::SignalPtr< dg::Vector, sigtime_t > freeFlyerVelocitySIN
Definition: dynamic-pinocchio.h:124
dynamicgraph::sot::DynamicPinocchio::createJacobianSignal
dg::SignalTimeDependent< dg::Matrix, sigtime_t > & createJacobianSignal(const std::string &signame, const std::string &)
Definition: sot-dynamic-pinocchio.cpp:509
dynamicgraph::Matrix
Eigen::MatrixXd Matrix
f
void f(void)
dynamicgraph::sot::ExceptionDynamic::CANT_DESTROY_SIGNAL
CANT_DESTROY_SIGNAL
dynamicgraph::sot::ExceptionSignal::BAD_CAST
BAD_CAST
pinocchio::getJointJacobian
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &J)
pinocchio::FrameTpl
dynamicgraph::Entity::getName
const std::string & getName() const
dynamicgraph::sot::command::DisplayModel
Definition: dynamic-command.h:26
tau
tau
dynamicgraph::sot::DynamicPinocchio::createEndeffJacobianSignal
dg::SignalTimeDependent< dg::Matrix, sigtime_t > & createEndeffJacobianSignal(const std::string &signame, const std::string &, const bool isLocal=true)
Definition: sot-dynamic-pinocchio.cpp:540
res
res
dynamicgraph::SignalPtr::access
virtual const T & access(const Time &t)
dynamicgraph::sot::DynamicPinocchio::gearRatioSOUT
dg::Signal< dg::Vector, sigtime_t > gearRatioSOUT
Definition: dynamic-pinocchio.h:163
dynamicgraph::sot::DynamicPinocchio::cmd_createVelocitySignal
void cmd_createVelocitySignal(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1119
sotDEBUGOUT
#define sotDEBUGOUT(level)
dynamicgraph::sot::DynamicPinocchio::destroyAccelerationSignal
void destroyAccelerationSignal(const std::string &signame)
Definition: sot-dynamic-pinocchio.cpp:717
dynamicgraph::sot::DynamicPinocchio::computeJcom
dg::Matrix & computeJcom(dg::Matrix &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:932
dynamicgraph::sot::DynamicPinocchio::destroyJacobianSignal
void destroyJacobianSignal(const std::string &signame)
Definition: sot-dynamic-pinocchio.cpp:642
pinocchio::rnea
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
dynamicgraph::sot::command::GetDimension
Definition: dynamic-command.h:45
dynamicgraph::sot::DynamicPinocchio::destroyVelocitySignal
void destroyVelocitySignal(const std::string &signame)
Definition: sot-dynamic-pinocchio.cpp:692
pinocchio::centerOfMass
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
dynamicgraph::sot::DynamicPinocchio::inertiaRotorSOUT
dg::Signal< dg::Vector, sigtime_t > inertiaRotorSOUT
Definition: dynamic-pinocchio.h:162
dynamicgraph::sot::DynamicPinocchio::getLowerPositionLimits
dg::Vector & getLowerPositionLimits(dg::Vector &res, const sigtime_t &) const
Get joint position lower limits.
Definition: sot-dynamic-pinocchio.cpp:318
pinocchio::ModelTpl::getFrameId
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
dynamicgraph::sot::DynamicPinocchio::freeFlyerPositionSIN
dg::SignalPtr< dg::Vector, sigtime_t > freeFlyerPositionSIN
Definition: dynamic-pinocchio.h:122
dynamicgraph::sot::DynamicPinocchio::newtonEulerSINTERN
dg::SignalTimeDependent< Dummy, sigtime_t > newtonEulerSINTERN
Definition: dynamic-pinocchio.h:132
dynamicgraph::sot::DynamicPinocchio::cmd_createJacobianEndEffectorWorldSignal
void cmd_createJacobianEndEffectorWorldSignal(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1110
dynamicgraph::sot::DynamicPinocchio::MomentaSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > MomentaSOUT
Definition: dynamic-pinocchio.h:165
sotDEBUGIN
#define sotDEBUGIN(level)
dynamicgraph::sot::DynamicPinocchio::setModel
void setModel(pinocchio::Model *)
Definition: sot-dynamic-pinocchio.cpp:297
pinocchio::ForceTpl
dynamicgraph::sot::DynamicPinocchio::computeGenericJacobian
dg::Matrix & computeGenericJacobian(const bool isFrame, const int jointId, dg::Matrix &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:803
dynamicgraph::sot::DynamicPinocchio::genericSignalRefs
std::list< dg::SignalBase< sigtime_t > * > genericSignalRefs
Definition: dynamic-pinocchio.h:116
sig
dynamicgraph::SignalArray_const< double > sig
dynamicgraph::sot::DynamicPinocchio::footHeightSOUT
dg::SignalTimeDependent< double, sigtime_t > footHeightSOUT
Definition: dynamic-pinocchio.h:156
dummy
DummyClass dummy
kineromeo.inertiaRotor
tuple inertiaRotor
Definition: kineromeo.py:93
dynamicgraph::sot::DynamicPinocchio::cmd_createOpPointSignals
void cmd_createOpPointSignals(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1096
dynamicgraph::sot::DynamicPinocchio::jointPositionSIN
dg::SignalPtr< dg::Vector, sigtime_t > jointPositionSIN
Definition: dynamic-pinocchio.h:121
dynamicgraph::sot::DynamicPinocchio::computeMomenta
dg::Vector & computeMomenta(dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:1005
dynamicgraph::sot::DynamicPinocchio::computeCom
dg::Vector & computeCom(dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:941
dynamicgraph::sotNOSIGNAL
SignalArray< int > sotNOSIGNAL(0)
pinocchio::computeJointJacobians
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
M
M
dynamicgraph::sot::DynamicPinocchio::getPinocchioAcc
dg::Vector & getPinocchioAcc(dg::Vector &a, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:492
pinocchio::ModelTpl::velocityLimit
TangentVectorType velocityLimit
dynamicgraph::sot::DynamicPinocchio::JcomSOUT
dg::SignalTimeDependent< dg::Matrix, sigtime_t > JcomSOUT
Definition: dynamic-pinocchio.h:143
dynamicgraph::sot::DynamicPinocchio::velocitiesSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > & velocitiesSOUT(const std::string &name)
Definition: sot-dynamic-pinocchio.cpp:1061
dynamicgraph::sot::DynamicPinocchio::pinocchioVelSINTERN
dg::SignalTimeDependent< dg::Vector, sigtime_t > pinocchioVelSINTERN
Definition: dynamic-pinocchio.h:129
q
q
dynamicgraph::Vector
Eigen::VectorXd Vector
dynamicgraph::sot::DynamicPinocchio::createData
void createData()
Definition: sot-dynamic-pinocchio.cpp:312
dynamicgraph::sot::DynamicPinocchio::createVelocitySignal
dg::SignalTimeDependent< dg::Vector, sigtime_t > & createVelocitySignal(const std::string &, const std::string &)
Definition: sot-dynamic-pinocchio.cpp:603
a
Vec3f a
makeCommandVoid2
CommandVoid2< E, T1, T2 > * makeCommandVoid2(E &entity, boost::function< void(const T1 &, const T2 &)> function, const std::string &docString)
pinocchio::ModelTpl::getJointId
JointIndex getJointId(const std::string &name) const
docCommandVoid2
std::string docCommandVoid2(const std::string &doc, const std::string &type1, const std::string &type2)
dynamicgraph::sot::DynamicPinocchio::~DynamicPinocchio
virtual ~DynamicPinocchio(void)
Definition: sot-dynamic-pinocchio.cpp:280
dynamicgraph::sot::DynamicPinocchio::computeGenericVelocity
dg::Vector & computeGenericVelocity(const int jointId, dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:892
dynamicgraph::sot::DynamicPinocchio::computeNewtonEuler
int & computeNewtonEuler(int &dummy, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:915
dynamicgraph::sot::DynamicPinocchio::createAccelerationSignal
dg::SignalTimeDependent< dg::Vector, sigtime_t > & createAccelerationSignal(const std::string &, const std::string &)
Definition: sot-dynamic-pinocchio.cpp:623
dynamicgraph::SignalTimeDependent< dg::Matrix, sigtime_t >
ForceDense< ForceTpl< _Scalar, _Options > >::angular
AngularType angular()
dynamicgraph::sot::DynamicPinocchio::getPinocchioPos
dg::Vector & getPinocchioPos(dg::Vector &q, const sigtime_t &time)
map of joints in construction. map: jointName -> (jointType,jointPosition (in parent frame),...
Definition: sot-dynamic-pinocchio.cpp:431
dynamicgraph::sot::DynamicPinocchio::computeTorqueDrift
dg::Vector & computeTorqueDrift(dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:996
dynamicgraph::sot::DynamicPinocchio::destroyPositionSignal
void destroyPositionSignal(const std::string &signame)
Definition: sot-dynamic-pinocchio.cpp:666
dynamicgraph::sot::DynamicPinocchio::computeForwardKinematics
int & computeForwardKinematics(int &dummy, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:779
dynamicgraph::sot::DynamicPinocchio::inertiaSOUT
dg::SignalTimeDependent< dg::Matrix, sigtime_t > inertiaSOUT
Definition: dynamic-pinocchio.h:145
pinocchio::ModelTpl::nv
int nv
dynamicgraph::sot
ForceDense< ForceTpl< _Scalar, _Options > >::linear
LinearType linear()
dynamicgraph::sot::DynamicPinocchio::computeGenericAcceleration
dg::Vector & computeGenericAcceleration(const int jointId, dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:904
dynamicgraph::sot::DynamicPinocchio::getUpperPositionLimits
dg::Vector & getUpperPositionLimits(dg::Vector &res, const sigtime_t &) const
Get joint position upper limits.
Definition: sot-dynamic-pinocchio.cpp:365
dynamicgraph::sot::DynamicPinocchio::positionsSOUT
dg::SignalTimeDependent< MatrixHomogeneous, sigtime_t > & positionsSOUT(const std::string &name)
Definition: sot-dynamic-pinocchio.cpp:1046
dynamicgraph::sot::DynamicPinocchio::lowerJlSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > lowerJlSOUT
Definition: dynamic-pinocchio.h:158
v
v
dynamicgraph::Entity::signalRegistration
void signalRegistration(const SignalArray< int > &signals)
dynamicgraph::sot::DynamicPinocchio::createPositionSignal
dg::SignalTimeDependent< MatrixHomogeneous, sigtime_t > & createPositionSignal(const std::string &, const std::string &)
Definition: sot-dynamic-pinocchio.cpp:572
pinocchio::JointIndex
Index JointIndex
pinocchio::updateFramePlacement
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & updateFramePlacement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
dynamicgraph::sot::ExceptionDynamic::GENERIC
GENERIC
pinocchio::ModelTpl::effortLimit
TangentVectorType effortLimit
dynamicgraph::sot::DynamicPinocchio::accelerationsSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > & accelerationsSOUT(const std::string &name)
Definition: sot-dynamic-pinocchio.cpp:1075
dynamicgraph::Entity::addCommand
void addCommand(const std::string &name, command::Command *command)
dynamicgraph::sot::DynamicPinocchio::DynamicPinocchio
DynamicPinocchio(const std::string &name)
Definition: sot-dynamic-pinocchio.cpp:32
pinocchio::crba
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
dynamicgraph::sot::DynamicPinocchio::getUpperVelocityLimits
dg::Vector & getUpperVelocityLimits(dg::Vector &res, const sigtime_t &) const
Get joint velocity upper limits.
Definition: sot-dynamic-pinocchio.cpp:405
dynamicgraph::Entity::getSignal
SignalBase< int > & getSignal(const std::string &signalName)
pinocchio::FrameTpl::parent
JointIndex parent
dynamicgraph::SignalTimeDependent::needUpdate
virtual bool needUpdate(const Time &t) const
all-commands.h
pinocchio::motionSet::se3Action
static void se3Action(const SE3Tpl< Scalar, Options > &m, const Eigen::MatrixBase< Mat > &iV, Eigen::MatrixBase< MatRet > const &jV)
dynamicgraph::sot::DynamicPinocchio::upperTlSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > upperTlSOUT
Definition: dynamic-pinocchio.h:160
pinocchio::MotionTpl
SOT_THROW
#define SOT_THROW
pinocchio::ModelTpl
dynamicgraph::sot::DynamicPinocchio::getPinocchioVel
dg::Vector & getPinocchioVel(dg::Vector &v, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:477
dynamicgraph::sot::DynamicPinocchio::computeZmp
dg::Vector & computeZmp(dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:748
dynamicgraph::SignalBase
A
A
dynamicgraph::Entity::signalDeregistration
void signalDeregistration(const std::string &name)
pinocchio::ModelTpl::upperPositionLimit
ConfigVectorType upperPositionLimit
dynamicgraph::sot::DynamicPinocchio::cmd_createJacobianWorldSignal
void cmd_createJacobianWorldSignal(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1101
dynamicgraph::sot::DynamicPinocchio::jointAccelerationSIN
dg::SignalPtr< dg::Vector, sigtime_t > jointAccelerationSIN
Definition: dynamic-pinocchio.h:125
dynamicgraph::sot::DynamicPinocchio::computeGenericPosition
MatrixHomogeneous & computeGenericPosition(const bool isFrame, const int jointId, MatrixHomogeneous &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:873
dynamicgraph::sot::DynamicPinocchio::AngularMomentumSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > AngularMomentumSOUT
Definition: dynamic-pinocchio.h:166
pinocchio::ModelTpl::nq
int nq
dynamicgraph::sot::command::GetJointNames
Definition: dynamic-command.h:64
com
com
dynamicgraph::sot::DynamicPinocchio::dynamicDriftSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > dynamicDriftSOUT
Definition: dynamic-pinocchio.h:167
dynamicgraph::sot::DynamicPinocchio::jacobiansSINTERN
dg::SignalTimeDependent< Dummy, sigtime_t > jacobiansSINTERN
Definition: dynamic-pinocchio.h:133
compile.name
name
Definition: compile.py:22
dynamicgraph::sot::DynamicPinocchio::cmd_createAccelerationSignal
void cmd_createAccelerationSignal(const std::string &sig, const std::string &j)
Definition: sot-dynamic-pinocchio.cpp:1123
pinocchio::ModelTpl::njoints
int njoints
dynamicgraph::sot::DynamicPinocchio::computeAngularMomentum
dg::Vector & computeAngularMomentum(dg::Vector &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:1017
dynamicgraph::sot::DynamicPinocchio::computeInertia
dg::Matrix & computeInertia(dg::Matrix &res, const sigtime_t &time)
Definition: sot-dynamic-pinocchio.cpp:953
sotDEBUG
#define sotDEBUG(level)
pinocchio::LOCAL
LOCAL


sot-dynamic-pinocchio
Author(s): Olivier Stasse
autogenerated on Fri Jul 28 2023 02:10:01