DART  6.7.3
GenericJoint.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2019, The DART development contributors
3  * All rights reserved.
4  *
5  * The list of contributors can be found at:
6  * https://github.com/dartsim/dart/blob/master/LICENSE
7  *
8  * This file is provided under the following "BSD-style" License:
9  * Redistribution and use in source and binary forms, with or
10  * without modification, are permitted provided that the following
11  * conditions are met:
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef DART_DYNAMICS_DETAIL_GenericJoint_HPP_
34 #define DART_DYNAMICS_DETAIL_GenericJoint_HPP_
35 
37 
38 #include "dart/config.hpp"
39 #include "dart/math/Helpers.hpp"
43 
44 #define GenericJoint_REPORT_DIM_MISMATCH( func, arg )\
45  {\
46  dterr << "[GenericJoint::" #func "] Mismatch beteween size of "\
47  << #arg " [" << arg .size() << "] and the number of "\
48  << "DOFs [" << getNumDofs() << "] for Joint named ["\
49  << this->getName() << "].\n";\
50  assert(false);\
51  }
52 
53 #define GenericJoint_REPORT_OUT_OF_RANGE( func, index )\
54  {\
55  dterr << "[GenericJoint::" << #func << "] The index [" << index\
56  << "] is out of range for Joint named [" << this->getName()\
57  << "] which has " << this->getNumDofs() << " DOFs.\n";\
58  assert(false);\
59  }
60 
61 #define GenericJoint_REPORT_UNSUPPORTED_ACTUATOR( func )\
62  {\
63  dterr << "[GenericJoint::" # func "] Unsupported actuator type ("\
64  << Joint::mAspectProperties.mActuatorType << ") for Joint ["\
65  << this->getName() << "].\n";\
66  assert(false);\
67  }
68 
69 #define GenericJoint_SET_IF_DIFFERENT( mField, value )\
70  if( value == Base::mAspectProperties. mField )\
71  return;\
72  Base::mAspectProperties. mField = value;\
73  Joint::incrementVersion();
74 
75 namespace dart {
76 namespace dynamics {
77 
78 //==============================================================================
79 //
80 // These namespace-level definitions are required to enable ODR-use of static
81 // constexpr member variables.
82 //
83 // See this StackOverflow answer: http://stackoverflow.com/a/14396189/111426
84 //
85 template <class ConfigSpaceT>
87 
88 //==============================================================================
89 template <class ConfigSpaceT>
91 {
92  for (auto i = 0u; i < NumDofs; ++i)
93  delete mDofs[i];
94 }
95 
96 //==============================================================================
97 template <class ConfigSpaceT>
99 {
100  Joint::setProperties(static_cast<const Joint::Properties&>(properties));
101  setProperties(static_cast<const UniqueProperties&>(properties));
102 }
103 
104 //==============================================================================
105 template <class ConfigSpaceT>
108 {
109  setAspectProperties(properties);
110 }
111 
112 //==============================================================================
113 template <class ConfigSpaceT>
115 {
116  setCommands(state.mCommands);
117  setPositionsStatic(state.mPositions);
118  setVelocitiesStatic(state.mVelocities);
119  setAccelerationsStatic(state.mAccelerations);
120  setForces(state.mForces);
121 }
122 
123 //==============================================================================
124 template <class ConfigSpaceT>
127 {
128  for (auto i = 0u; i < NumDofs; ++i)
129  {
130  setDofName(i, properties.mDofNames[i], properties.mPreserveDofNames[i]);
131  setPositionLowerLimit (i, properties.mPositionLowerLimits[i] );
132  setPositionUpperLimit (i, properties.mPositionUpperLimits[i] );
133  setInitialPosition (i, properties.mInitialPositions[i] );
134  setVelocityLowerLimit (i, properties.mVelocityLowerLimits[i] );
135  setVelocityUpperLimit (i, properties.mVelocityUpperLimits[i] );
136  setInitialVelocity (i, properties.mInitialVelocities[i] );
137  setAccelerationLowerLimit(i, properties.mAccelerationLowerLimits[i]);
138  setAccelerationUpperLimit(i, properties.mAccelerationUpperLimits[i]);
139  setForceLowerLimit (i, properties.mForceLowerLimits[i] );
140  setForceUpperLimit (i, properties.mForceUpperLimits[i] );
141  setSpringStiffness (i, properties.mSpringStiffnesses[i] );
142  setRestPosition (i, properties.mRestPositions[i] );
143  setDampingCoefficient (i, properties.mDampingCoefficients[i] );
144  setCoulombFriction (i, properties.mFrictions[i] );
145  }
146 }
147 
148 //==============================================================================
149 template <class ConfigSpaceT>
152 {
154  Joint::mAspectProperties, Base::mAspectProperties);
155 }
156 
157 //==============================================================================
158 template <class ConfigSpaceT>
160  const GenericJoint<ConfigSpaceT>& other)
161 {
162  if (this == &other)
163  return;
164 
165  setProperties(other.getGenericJointProperties());
166 }
167 
168 //==============================================================================
169 template <class ConfigSpaceT>
171  const GenericJoint<ConfigSpaceT>* other)
172 {
173  if (nullptr == other)
174  return;
175 
176  copy(*other);
177 }
178 
179 //==============================================================================
180 template <class ConfigSpaceT>
183  const GenericJoint<ConfigSpaceT>& other)
184 {
185  copy(other);
186  return *this;
187 }
188 
189 //==============================================================================
190 template <class ConfigSpaceT>
192 {
193  if (index < NumDofs)
194  return mDofs[index];
195 
197 
198  return nullptr;
199 }
200 
201 //==============================================================================
202 template <class ConfigSpaceT>
204 {
205  if (index < NumDofs)
206  return mDofs[index];
207 
209 
210  return nullptr;
211 }
212 
213 //==============================================================================
214 template <class ConfigSpaceT>
216 {
217  return NumDofs;
218 }
219 
220 //==============================================================================
221 template <class ConfigSpaceT>
223  size_t index,
224  const std::string& name,
225  bool preserveName)
226 {
227  if (NumDofs <= index)
228  {
229  dterr << "[GenericJoint::setDofName] Attempting to set the name of DOF "
230  << "index " << index << ", which is out of bounds for the Joint ["
231  << this->getName()
232  << "]. We will set the name of DOF index 0 instead.\n";
233  assert(false);
234  index = 0u;
235  }
236 
237  preserveDofName(index, preserveName);
238 
239  std::string& dofName = Base::mAspectProperties.mDofNames[index];
240 
241  if (name == dofName)
242  return dofName;
243 
244  const SkeletonPtr& skel
245  = this->mChildBodyNode ? this->mChildBodyNode->getSkeleton() : nullptr;
246  if (skel)
247  dofName = skel->mNameMgrForDofs.changeObjectName(mDofs[index], name);
248  else
249  dofName = name;
250 
251  return dofName;
252 }
253 
254 //==============================================================================
255 template <class ConfigSpaceT>
257 {
258  if (NumDofs <= index)
259  {
261  return;
262  }
263 
264  GenericJoint_SET_IF_DIFFERENT( mPreserveDofNames[index], preserve );
265 }
266 
267 //==============================================================================
268 template <class ConfigSpaceT>
270 {
271  if(NumDofs <= index)
272  {
273  GenericJoint_REPORT_OUT_OF_RANGE(isDofNamePreserved, index);
274  index = 0;
275  }
276 
277  return Base::mAspectProperties.mPreserveDofNames[index];
278 }
279 
280 //==============================================================================
281 template <class ConfigSpaceT>
282 const std::string& GenericJoint<ConfigSpaceT>::getDofName(size_t index) const
283 {
284  if(NumDofs <= index)
285  {
286  dterr << "[GenericJoint::getDofName] Requested name of DOF index ["
287  << index << "] in Joint [" << this->getName() << "], but that is "
288  << "out of bounds (max " << NumDofs - 1
289  << "). Returning name of DOF 0.\n";
290  assert(false);
291  return Base::mAspectProperties.mDofNames[0];
292  }
293 
294  return Base::mAspectProperties.mDofNames[index];
295 }
296 
297 //==============================================================================
298 template <class ConfigSpaceT>
299 size_t
301 {
302  if (index >= getNumDofs())
303  {
304  GenericJoint_REPORT_OUT_OF_RANGE(getIndexInSkeleton, index);
305  return 0;
306  }
307 
308  return mDofs[index]->mIndexInSkeleton;
309 }
310 
311 //==============================================================================
312 template <class ConfigSpaceT>
314 {
315  if (index >= getNumDofs())
316  {
318  return 0;
319  }
320 
321  return mDofs[index]->mIndexInTree;
322 }
323 
324 //==============================================================================
325 template <class ConfigSpaceT>
326 void GenericJoint<ConfigSpaceT>::setCommand(size_t index, double command)
327 {
328  if (index >= getNumDofs())
330 
331  switch (Joint::mAspectProperties.mActuatorType)
332  {
333  case Joint::FORCE:
334  this->mAspectState.mCommands[index] = math::clip(command,
335  Base::mAspectProperties.mForceLowerLimits[index],
336  Base::mAspectProperties.mForceUpperLimits[index]);
337  break;
339  if (0.0 != command)
340  {
341  dtwarn << "[GenericJoint::setCommand] Attempting to set a non-zero ("
342  << command << ") command for a PASSIVE joint ["
343  << this->getName() << "].\n";
344  }
345  this->mAspectState.mCommands[index] = command;
346  break;
348  this->mAspectState.mCommands[index] = math::clip(command,
349  Base::mAspectProperties.mVelocityLowerLimits[index],
350  Base::mAspectProperties.mVelocityUpperLimits[index]);
351  break;
352  case Joint::MIMIC:
353  if (0.0 != command)
354  {
355  dtwarn << "[GenericJoint::setCommand] Attempting to set a non-zero ("
356  << command << ") command for a MIMIC joint ["
357  << this->getName() << "].\n";
358  }
359  this->mAspectState.mCommands[index] = math::clip(command,
360  Base::mAspectProperties.mVelocityLowerLimits[index],
361  Base::mAspectProperties.mVelocityUpperLimits[index]);
362  break;
363  case Joint::ACCELERATION:
364  this->mAspectState.mCommands[index] = math::clip(command,
365  Base::mAspectProperties.mAccelerationLowerLimits[index],
366  Base::mAspectProperties.mAccelerationUpperLimits[index]);
367  break;
369  this->mAspectState.mCommands[index] = math::clip(command,
370  Base::mAspectProperties.mVelocityLowerLimits[index],
371  Base::mAspectProperties.mVelocityUpperLimits[index]);
372  // TODO: This possibly makes the acceleration to exceed the limits.
373  break;
375  if (0.0 != command)
376  {
377  dtwarn << "[GenericJoint::setCommand] Attempting to set a non-zero ("
378  << command << ") command for a LOCKED joint [" << this->getName()
379  << "].\n";
380  }
381  this->mAspectState.mCommands[index] = command;
382  break;
383  default:
384  assert(false);
385  break;
386  }
387 }
388 
389 //==============================================================================
390 template <class ConfigSpaceT>
392 {
393  if (index >= getNumDofs())
394  {
396  return 0.0;
397  }
398 
399  return this->mAspectState.mCommands[index];
400 }
401 
402 //==============================================================================
403 template <class ConfigSpaceT>
405  const Eigen::VectorXd& commands)
406 {
407  if (static_cast<size_t>(commands.size()) != getNumDofs())
408  {
409  GenericJoint_REPORT_DIM_MISMATCH(setCommands, commands);
410  return;
411  }
412 
413  switch (Joint::mAspectProperties.mActuatorType)
414  {
415  case Joint::FORCE:
416  this->mAspectState.mCommands = math::clip(commands,
417  Base::mAspectProperties.mForceLowerLimits,
418  Base::mAspectProperties.mForceUpperLimits);
419  break;
420  case Joint::PASSIVE:
421  if(Vector::Zero() != commands)
422  {
423  dtwarn << "[GenericJoint::setCommands] Attempting to set a non-zero ("
424  << commands.transpose() << ") command for a PASSIVE joint ["
425  << this->getName() << "].\n";
426  }
427  this->mAspectState.mCommands = commands;
428  break;
429  case Joint::SERVO:
430  this->mAspectState.mCommands = math::clip(commands,
431  Base::mAspectProperties.mVelocityLowerLimits,
432  Base::mAspectProperties.mVelocityUpperLimits);
433  break;
435  if(Vector::Zero() != commands)
436  {
437  dtwarn << "[GenericJoint::setCommands] Attempting to set a non-zero ("
438  << commands.transpose() << ") command for a MIMIC joint ["
439  << this->getName() << "].\n";
440  }
441  this->mAspectState.mCommands = math::clip(commands,
442  Base::mAspectProperties.mVelocityLowerLimits,
443  Base::mAspectProperties.mVelocityUpperLimits);
444  break;
445  case Joint::ACCELERATION:
446  this->mAspectState.mCommands = math::clip(commands,
447  Base::mAspectProperties.mAccelerationLowerLimits,
448  Base::mAspectProperties.mAccelerationUpperLimits);
449  break;
450  case Joint::VELOCITY:
451  this->mAspectState.mCommands = math::clip(commands,
452  Base::mAspectProperties.mVelocityLowerLimits,
453  Base::mAspectProperties.mVelocityUpperLimits);
454  // TODO: This possibly makes the acceleration to exceed the limits.
455  break;
456  case Joint::LOCKED:
457  if(Vector::Zero() != commands)
458  {
459  dtwarn << "[GenericJoint::setCommands] Attempting to set a non-zero ("
460  << commands.transpose() << ") command for a LOCKED joint ["
461  << this->getName() << "].\n";
462  }
463  this->mAspectState.mCommands = commands;
464  break;
465  default:
466  assert(false);
467  break;
468  }
469 }
470 
471 //==============================================================================
472 template <class ConfigSpaceT>
474 {
475  return this->mAspectState.mCommands;
476 }
477 
478 //==============================================================================
479 template <class ConfigSpaceT>
481 {
482  this->mAspectState.mCommands.setZero();
483 }
484 
485 //==============================================================================
486 template <class ConfigSpaceT>
488 {
489  if (index >= getNumDofs())
490  {
492  return;
493  }
494 
495  if (this->mAspectState.mPositions[index] == position)
496  return;
497  // TODO(JS): Above code should be changed something like:
498 // if (ConfigSpaceT::getEuclideanPoint(mPositions, index) == position)
499 // return;
500 
501  // Note: It would not make much sense to use setPositionsStatic() here
502  this->mAspectState.mPositions[index] = position;
503  this->notifyPositionUpdated();
504 }
505 
506 //==============================================================================
507 template <class ConfigSpaceT>
509 {
510  if (index >= getNumDofs())
511  {
513  return 0.0;
514  }
515 
516  return getPositionsStatic()[index];
517 }
518 
519 //==============================================================================
520 template <class ConfigSpaceT>
522  const Eigen::VectorXd& positions)
523 {
524  if (static_cast<size_t>(positions.size()) != getNumDofs())
525  {
526  GenericJoint_REPORT_DIM_MISMATCH(setPositions, positions);
527  return;
528  }
529 
530  setPositionsStatic(positions);
531 }
532 
533 //==============================================================================
534 template <class ConfigSpaceT>
536 {
537  return getPositionsStatic();
538 }
539 
540 //==============================================================================
541 template <class ConfigSpaceT>
543  size_t index, double position)
544 {
545  if (index >= getNumDofs())
546  {
547  GenericJoint_REPORT_OUT_OF_RANGE(setPositionLowerLimit, index);
548  return;
549  }
550 
551  GenericJoint_SET_IF_DIFFERENT( mPositionLowerLimits[index], position );
552 }
553 
554 //==============================================================================
555 template <class ConfigSpaceT>
557 {
558  if (index >= getNumDofs())
559  {
560  GenericJoint_REPORT_OUT_OF_RANGE(getPositionLowerLimit, index);
561  return 0.0;
562  }
563 
564  return Base::mAspectProperties.mPositionLowerLimits[index];
565 }
566 
567 //==============================================================================
568 template<class ConfigSpaceT>
570  const Eigen::VectorXd& lowerLimits)
571 {
572  if (static_cast<size_t>(lowerLimits.size()) != getNumDofs())
573  {
574  GenericJoint_REPORT_DIM_MISMATCH(setPositionLowerLimits, lowerLimits);
575  return;
576  }
577 
578  GenericJoint_SET_IF_DIFFERENT(mPositionLowerLimits, lowerLimits);
579 }
580 
581 //==============================================================================
582 template<class ConfigSpaceT>
584 {
585  return Base::mAspectProperties.mPositionLowerLimits;
586 }
587 
588 //==============================================================================
589 template <class ConfigSpaceT>
591  double position)
592 {
593  if (index >= getNumDofs())
594  {
595  GenericJoint_REPORT_OUT_OF_RANGE(setPositionUpperLimit, index);
596  return;
597  }
598 
599  GenericJoint_SET_IF_DIFFERENT( mPositionUpperLimits[index], position );
600 }
601 
602 //==============================================================================
603 template <class ConfigSpaceT>
605 {
606  if (index >= getNumDofs())
607  {
608  GenericJoint_REPORT_OUT_OF_RANGE(getPositionUpperLimit, index);
609  return 0.0;
610  }
611 
612  return Base::mAspectProperties.mPositionUpperLimits[index];
613 }
614 
615 //==============================================================================
616 template<class ConfigSpaceT>
618  const Eigen::VectorXd& upperLimits)
619 {
620  if (static_cast<size_t>(upperLimits.size()) != getNumDofs())
621  {
622  GenericJoint_REPORT_DIM_MISMATCH(setPositionUpperLimits, upperLimits);
623  return;
624  }
625 
626  GenericJoint_SET_IF_DIFFERENT(mPositionUpperLimits, upperLimits);
627 }
628 
629 //==============================================================================
630 template<class ConfigSpaceT>
632 {
633  return Base::mAspectProperties.mPositionUpperLimits;
634 }
635 
636 //==============================================================================
637 template <class ConfigSpaceT>
639 {
640  if (index >= getNumDofs())
641  {
643  return true;
644  }
645 
646  return std::isfinite(Base::mAspectProperties.mPositionUpperLimits[index])
647  || std::isfinite(Base::mAspectProperties.mPositionLowerLimits[index]);
648 }
649 
650 //==============================================================================
651 template <class ConfigSpaceT>
653 {
654  if (index >= getNumDofs())
655  {
656  GenericJoint_REPORT_OUT_OF_RANGE(resetPosition, index);
657  return;
658  }
659 
660  setPosition(index, Base::mAspectProperties.mInitialPositions[index]);
661 }
662 
663 //==============================================================================
664 template <class ConfigSpaceT>
666 {
667  setPositionsStatic(Base::mAspectProperties.mInitialPositions);
668 }
669 
670 //==============================================================================
671 template <class ConfigSpaceT>
673  size_t index, double initial)
674 {
675  if (index >= getNumDofs())
676  {
677  GenericJoint_REPORT_OUT_OF_RANGE(setInitialPosition, index);
678  return;
679  }
680 
681  GenericJoint_SET_IF_DIFFERENT( mInitialPositions[index], initial );
682 }
683 
684 //==============================================================================
685 template <class ConfigSpaceT>
687 {
688  if (index >= getNumDofs())
689  {
690  GenericJoint_REPORT_OUT_OF_RANGE(getInitialPosition, index);
691  return 0.0;
692  }
693 
694  return Base::mAspectProperties.mInitialPositions[index];
695 }
696 
697 //==============================================================================
698 template <class ConfigSpaceT>
700  const Eigen::VectorXd& initial)
701 {
702  if ( static_cast<size_t>(initial.size()) != getNumDofs() )
703  {
704  GenericJoint_REPORT_DIM_MISMATCH(setInitialPositions, initial);
705  return;
706  }
707 
708  GenericJoint_SET_IF_DIFFERENT( mInitialPositions, initial);
709 }
710 
711 //==============================================================================
712 template <class ConfigSpaceT>
714 {
715  return Base::mAspectProperties.mInitialPositions;
716 }
717 
718 //==============================================================================
719 template <class ConfigSpaceT>
721 {
722  if (this->mAspectState.mPositions == positions)
723  return;
724 
725  this->mAspectState.mPositions = positions;
726  this->notifyPositionUpdated();
727 }
728 
729 //==============================================================================
730 template <class ConfigSpaceT>
733 {
734  return this->mAspectState.mPositions;
735 }
736 
737 //==============================================================================
738 template <class ConfigSpaceT>
740  const Vector& velocities)
741 {
742  if (this->mAspectState.mVelocities == velocities)
743  return;
744 
745  this->mAspectState.mVelocities = velocities;
746  this->notifyVelocityUpdated();
747 }
748 
749 //==============================================================================
750 template <class ConfigSpaceT>
753 {
754  return this->mAspectState.mVelocities;
755 }
756 
757 //==============================================================================
758 template <class ConfigSpaceT>
760 {
761  if (this->mAspectState.mAccelerations == accels)
762  return;
763 
764  this->mAspectState.mAccelerations = accels;
765  this->notifyAccelerationUpdated();
766 }
767 
768 //==============================================================================
769 template <class ConfigSpaceT>
772 {
773  return this->mAspectState.mAccelerations;
774 }
775 
776 //==============================================================================
777 template <class ConfigSpaceT>
779 {
780  if (index >= getNumDofs())
781  {
783  return;
784  }
785 
786  if (this->mAspectState.mVelocities[index] == velocity)
787  return;
788 
789  // Note: It would not make much sense to use setVelocitiesStatic() here
790  this->mAspectState.mVelocities[index] = velocity;
791  this->notifyVelocityUpdated();
792 
793  if (Joint::mAspectProperties.mActuatorType == Joint::VELOCITY)
794  this->mAspectState.mCommands[index] = this->getVelocitiesStatic()[index];
795 }
796 
797 //==============================================================================
798 template <class ConfigSpaceT>
800 {
801  if (index >= getNumDofs())
802  {
804  return 0.0;
805  }
806 
807  return getVelocitiesStatic()[index];
808 }
809 
810 //==============================================================================
811 template <class ConfigSpaceT>
813  const Eigen::VectorXd& velocities)
814 {
815  if (static_cast<size_t>(velocities.size()) != getNumDofs())
816  {
817  GenericJoint_REPORT_DIM_MISMATCH(setVelocities, velocities);
818  return;
819  }
820 
821  setVelocitiesStatic(velocities);
822 
823  if (Joint::mAspectProperties.mActuatorType == Joint::VELOCITY)
824  this->mAspectState.mCommands = this->getVelocitiesStatic();
825 }
826 
827 //==============================================================================
828 template <class ConfigSpaceT>
830 {
831  return getVelocitiesStatic();
832 }
833 
834 //==============================================================================
835 template <class ConfigSpaceT>
837  double velocity)
838 {
839  if (index >= getNumDofs())
840  {
841  GenericJoint_REPORT_OUT_OF_RANGE(setVelocityLowerLimit, index);
842  return;
843  }
844 
845  GenericJoint_SET_IF_DIFFERENT( mVelocityLowerLimits[index], velocity );
846 }
847 
848 //==============================================================================
849 template <class ConfigSpaceT>
851 {
852  if (index >= getNumDofs())
853  {
854  GenericJoint_REPORT_OUT_OF_RANGE(getVelocityLowerLimit, index);
855  return 0.0;
856  }
857 
858  return Base::mAspectProperties.mVelocityLowerLimits[index];
859 }
860 
861 //==============================================================================
862 template<class ConfigSpaceT>
864  const Eigen::VectorXd& lowerLimits)
865 {
866  if (static_cast<size_t>(lowerLimits.size()) != getNumDofs())
867  {
868  GenericJoint_REPORT_DIM_MISMATCH(setVelocityLowerLimits, lowerLimits);
869  return;
870  }
871 
872  GenericJoint_SET_IF_DIFFERENT(mVelocityLowerLimits, lowerLimits);
873 }
874 
875 //==============================================================================
876 template<class ConfigSpaceT>
878 {
879  return Base::mAspectProperties.mVelocityLowerLimits;
880 }
881 
882 //==============================================================================
883 template <class ConfigSpaceT>
885  double velocity)
886 {
887  if (index >= getNumDofs())
888  {
889  GenericJoint_REPORT_OUT_OF_RANGE(setVelocityUpperLimit, index);
890  return;
891  }
892 
893  GenericJoint_SET_IF_DIFFERENT( mVelocityUpperLimits[index], velocity );
894 }
895 
896 //==============================================================================
897 template <class ConfigSpaceT>
899  size_t index) const
900 {
901  if (index >= getNumDofs())
902  {
903  GenericJoint_REPORT_OUT_OF_RANGE(getVelocityUpperLimit, index);
904  return 0.0;
905  }
906 
907  return Base::mAspectProperties.mVelocityUpperLimits[index];
908 }
909 
910 //==============================================================================
911 template<class ConfigSpaceT>
913  const Eigen::VectorXd& upperLimits)
914 {
915  if (static_cast<size_t>(upperLimits.size()) != getNumDofs())
916  {
917  GenericJoint_REPORT_DIM_MISMATCH(setVelocityUpperLimits, upperLimits);
918  return;
919  }
920 
921  GenericJoint_SET_IF_DIFFERENT(mVelocityUpperLimits, upperLimits);
922 }
923 
924 //==============================================================================
925 template<class ConfigSpaceT>
927 {
928  return Base::mAspectProperties.mVelocityUpperLimits;
929 }
930 
931 //==============================================================================
932 template <class ConfigSpaceT>
934 {
935  if (index >= getNumDofs())
936  {
937  GenericJoint_REPORT_OUT_OF_RANGE(resetVelocity, index);
938  return;
939  }
940 
941  setVelocity(index, Base::mAspectProperties.mInitialVelocities[index]);
942 }
943 
944 //==============================================================================
945 template <class ConfigSpaceT>
947 {
948  setVelocitiesStatic(Base::mAspectProperties.mInitialVelocities);
949 }
950 
951 //==============================================================================
952 template <class ConfigSpaceT>
954  double initial)
955 {
956  if (index >= getNumDofs())
957  {
958  GenericJoint_REPORT_OUT_OF_RANGE(setInitialVelocity, index);
959  return;
960  }
961 
962  GenericJoint_SET_IF_DIFFERENT( mInitialVelocities[index], initial );
963 }
964 
965 //==============================================================================
966 template <class ConfigSpaceT>
968 {
969  if (index >= getNumDofs())
970  {
971  GenericJoint_REPORT_OUT_OF_RANGE(getInitialVelocity, index);
972  return 0.0;
973  }
974 
975  return Base::mAspectProperties.mInitialVelocities[index];
976 }
977 
978 //==============================================================================
979 template <class ConfigSpaceT>
981  const Eigen::VectorXd& initial)
982 {
983  if ( static_cast<size_t>(initial.size()) != getNumDofs() )
984  {
985  GenericJoint_REPORT_DIM_MISMATCH( setInitialVelocities, initial );
986  return;
987  }
988 
989  GenericJoint_SET_IF_DIFFERENT( mInitialVelocities, initial );
990 }
991 
992 //==============================================================================
993 template <class ConfigSpaceT>
995 {
996  return Base::mAspectProperties.mInitialVelocities;
997 }
998 
999 //==============================================================================
1000 template <class ConfigSpaceT>
1002  size_t index, double acceleration)
1003 {
1004  if (index >= getNumDofs())
1005  {
1006  GenericJoint_REPORT_OUT_OF_RANGE( setAcceleration, index );
1007  return;
1008  }
1009 
1010  if(this->mAspectState.mAccelerations[index] == acceleration)
1011  return;
1012 
1013  // Note: It would not make much sense to use setAccelerationsStatic() here
1014  this->mAspectState.mAccelerations[index] = acceleration;
1015  this->notifyAccelerationUpdated();
1016 
1017  if (Joint::mAspectProperties.mActuatorType == Joint::ACCELERATION)
1018  this->mAspectState.mCommands[index] = this->getAccelerationsStatic()[index];
1019 }
1020 
1021 //==============================================================================
1022 template <class ConfigSpaceT>
1024 {
1025  if (index >= getNumDofs())
1026  {
1027  GenericJoint_REPORT_OUT_OF_RANGE(getAcceleration, index);
1028  return 0.0;
1029  }
1030 
1031  return getAccelerationsStatic()[index];
1032 }
1033 
1034 //==============================================================================
1035 template <class ConfigSpaceT>
1037  const Eigen::VectorXd& accelerations)
1038 {
1039  if (static_cast<size_t>(accelerations.size()) != getNumDofs())
1040  {
1041  GenericJoint_REPORT_DIM_MISMATCH( setAccelerations, accelerations );
1042  return;
1043  }
1044 
1045  setAccelerationsStatic(accelerations);
1046 
1047  if (Joint::mAspectProperties.mActuatorType == Joint::ACCELERATION)
1048  this->mAspectState.mCommands = this->getAccelerationsStatic();
1049 }
1050 
1051 //==============================================================================
1052 template <class ConfigSpaceT>
1054 {
1055  return getAccelerationsStatic();
1056 }
1057 
1058 //==============================================================================
1059 template <class ConfigSpaceT>
1061  size_t index, double acceleration)
1062 {
1063  if (index >= getNumDofs())
1064  {
1065  GenericJoint_REPORT_OUT_OF_RANGE(setAccelerationLowerLimit, index);
1066  return;
1067  }
1068 
1069  GenericJoint_SET_IF_DIFFERENT( mAccelerationLowerLimits[index],
1070  acceleration );
1071 }
1072 
1073 //==============================================================================
1074 template <class ConfigSpaceT>
1076  size_t index) const
1077 {
1078  if (index >= getNumDofs())
1079  {
1080  GenericJoint_REPORT_OUT_OF_RANGE(getAccelerationLowerLimit, index);
1081  return 0.0;
1082  }
1083 
1084  return Base::mAspectProperties.mAccelerationLowerLimits[index];
1085 }
1086 
1087 //==============================================================================
1088 template<class ConfigSpaceT>
1090  const Eigen::VectorXd& lowerLimits)
1091 {
1092  if (static_cast<size_t>(lowerLimits.size()) != getNumDofs())
1093  {
1094  GenericJoint_REPORT_DIM_MISMATCH(setAccelerationLowerLimits, lowerLimits);
1095  return;
1096  }
1097 
1098  GenericJoint_SET_IF_DIFFERENT(mAccelerationLowerLimits, lowerLimits);
1099 }
1100 
1101 //==============================================================================
1102 template<class ConfigSpaceT>
1104 {
1105  return Base::mAspectProperties.mAccelerationLowerLimits;
1106 }
1107 
1108 //==============================================================================
1109 template <class ConfigSpaceT>
1111  size_t index, double acceleration)
1112 {
1113  if (index >= getNumDofs())
1114  {
1115  GenericJoint_REPORT_OUT_OF_RANGE(setAccelerationUpperLimit, index)
1116  return;
1117  }
1118 
1119  GenericJoint_SET_IF_DIFFERENT( mAccelerationUpperLimits[index],
1120  acceleration);
1121 }
1122 
1123 //==============================================================================
1124 template <class ConfigSpaceT>
1126  size_t index) const
1127 {
1128  if (index >= getNumDofs())
1129  {
1130  GenericJoint_REPORT_OUT_OF_RANGE(getAccelerationUpperLimit, index);
1131  return 0.0;
1132  }
1133 
1134  return Base::mAspectProperties.mAccelerationUpperLimits[index];
1135 }
1136 
1137 //==============================================================================
1138 template<class ConfigSpaceT>
1140  const Eigen::VectorXd& upperLimits)
1141 {
1142  if (static_cast<size_t>(upperLimits.size()) != getNumDofs())
1143  {
1144  GenericJoint_REPORT_DIM_MISMATCH(setAccelerationUpperLimits, upperLimits);
1145  return;
1146  }
1147 
1148  GenericJoint_SET_IF_DIFFERENT(mAccelerationUpperLimits, upperLimits);
1149 }
1150 
1151 //==============================================================================
1152 template<class ConfigSpaceT>
1154 {
1155  return Base::mAspectProperties.mAccelerationUpperLimits;
1156 }
1157 
1158 //==============================================================================
1159 template <class ConfigSpaceT>
1161 {
1162  setAccelerationsStatic(Vector::Zero());
1163 }
1164 
1165 //==============================================================================
1166 template <class ConfigSpaceT>
1168 {
1169  if (index >= getNumDofs())
1170  {
1172  return;
1173  }
1174 
1175  this->mAspectState.mForces[index] = force;
1176 
1177  if (Joint::mAspectProperties.mActuatorType == Joint::FORCE)
1178  this->mAspectState.mCommands[index] = this->mAspectState.mForces[index];
1179 }
1180 
1181 //==============================================================================
1182 template <class ConfigSpaceT>
1184 {
1185  if (index >= getNumDofs())
1186  {
1188  return 0.0;
1189  }
1190 
1191  return this->mAspectState.mForces[index];
1192 }
1193 
1194 //==============================================================================
1195 template <class ConfigSpaceT>
1196 void GenericJoint<ConfigSpaceT>::setForces(const Eigen::VectorXd& forces)
1197 {
1198  if (static_cast<size_t>(forces.size()) != getNumDofs())
1199  {
1200  GenericJoint_REPORT_DIM_MISMATCH(setForces, forces);
1201  return;
1202  }
1203 
1204  this->mAspectState.mForces = forces;
1205 
1206  if (Joint::mAspectProperties.mActuatorType == Joint::FORCE)
1207  this->mAspectState.mCommands = this->mAspectState.mForces;
1208 }
1209 
1210 //==============================================================================
1211 template <class ConfigSpaceT>
1213 {
1214  return this->mAspectState.mForces;
1215 }
1216 
1217 //==============================================================================
1218 template <class ConfigSpaceT>
1220 {
1221  if (index >= getNumDofs())
1222  {
1223  GenericJoint_REPORT_OUT_OF_RANGE(setForceLowerLimit, index);
1224  return;
1225  }
1226 
1227  GenericJoint_SET_IF_DIFFERENT( mForceLowerLimits[index], force );
1228 }
1229 
1230 //==============================================================================
1231 template <class ConfigSpaceT>
1233  size_t index) const
1234 {
1235  if (index >= getNumDofs())
1236  {
1237  GenericJoint_REPORT_OUT_OF_RANGE(getForceLowerLimit, index);
1238  return 0.0;
1239  }
1240 
1241  return Base::mAspectProperties.mForceLowerLimits[index];
1242 }
1243 
1244 //==============================================================================
1245 template<class ConfigSpaceT>
1247  const Eigen::VectorXd& lowerLimits)
1248 {
1249  if (static_cast<size_t>(lowerLimits.size()) != getNumDofs())
1250  {
1251  GenericJoint_REPORT_DIM_MISMATCH(setForceLowerLimits, lowerLimits);
1252  return;
1253  }
1254 
1255  GenericJoint_SET_IF_DIFFERENT(mForceLowerLimits, lowerLimits);
1256 }
1257 
1258 //==============================================================================
1259 template<class ConfigSpaceT>
1261 {
1262  return Base::mAspectProperties.mForceLowerLimits;
1263 }
1264 
1265 //==============================================================================
1266 template <class ConfigSpaceT>
1268 {
1269  if (index >= getNumDofs())
1270  {
1271  GenericJoint_REPORT_OUT_OF_RANGE(setForceUpperLimit, index);
1272  return;
1273  }
1274 
1275  GenericJoint_SET_IF_DIFFERENT( mForceUpperLimits[index], force );
1276 }
1277 
1278 //==============================================================================
1279 template <class ConfigSpaceT>
1281  size_t index) const
1282 {
1283  if (index >= getNumDofs())
1284  {
1285  GenericJoint_REPORT_OUT_OF_RANGE(getForceUpperLimit, index);
1286  return 0.0;
1287  }
1288 
1289  return Base::mAspectProperties.mForceUpperLimits[index];
1290 }
1291 
1292 //==============================================================================
1293 template<class ConfigSpaceT>
1295  const Eigen::VectorXd& upperLimits)
1296 {
1297  if (static_cast<size_t>(upperLimits.size()) != getNumDofs())
1298  {
1299  GenericJoint_REPORT_DIM_MISMATCH(setForceUpperLimits, upperLimits);
1300  return;
1301  }
1302 
1303  GenericJoint_SET_IF_DIFFERENT(mForceUpperLimits, upperLimits);
1304 }
1305 
1306 //==============================================================================
1307 template<class ConfigSpaceT>
1309 {
1310  return Base::mAspectProperties.mForceUpperLimits;
1311 }
1312 
1313 //==============================================================================
1314 template <class ConfigSpaceT>
1316 {
1317  this->mAspectState.mForces.setZero();
1318 
1319  if (Joint::mAspectProperties.mActuatorType == Joint::FORCE)
1320  this->mAspectState.mCommands = this->mAspectState.mForces;
1321 }
1322 
1323 //==============================================================================
1324 template <class ConfigSpaceT>
1326  size_t index, double velocityChange)
1327 {
1328  if (index >= getNumDofs())
1329  {
1330  GenericJoint_REPORT_OUT_OF_RANGE(setVelocityChange, index);
1331  return;
1332  }
1333 
1334  mVelocityChanges[index] = velocityChange;
1335 }
1336 
1337 //==============================================================================
1338 template <class ConfigSpaceT>
1340 {
1341  if (index >= getNumDofs())
1342  {
1343  GenericJoint_REPORT_OUT_OF_RANGE(getVelocityChange, index);
1344  return 0.0;
1345  }
1346 
1347  return mVelocityChanges[index];
1348 }
1349 
1350 //==============================================================================
1351 template <class ConfigSpaceT>
1353 {
1354  mVelocityChanges.setZero();
1355 }
1356 
1357 //==============================================================================
1358 template <class ConfigSpaceT>
1360  double impulse)
1361 {
1362  if (index >= getNumDofs())
1363  {
1364  GenericJoint_REPORT_OUT_OF_RANGE(setConstraintImpulse, index);
1365  return;
1366  }
1367 
1368  mConstraintImpulses[index] = impulse;
1369 }
1370 
1371 //==============================================================================
1372 template <class ConfigSpaceT>
1374 {
1375  if (index >= getNumDofs())
1376  {
1377  GenericJoint_REPORT_OUT_OF_RANGE(getConstraintImpulse, index);
1378  return 0.0;
1379  }
1380 
1381  return mConstraintImpulses[index];
1382 }
1383 
1384 //==============================================================================
1385 template <class ConfigSpaceT>
1387 {
1388  mConstraintImpulses.setZero();
1389 }
1390 
1391 //==============================================================================
1392 template <class ConfigSpaceT>
1394 {
1395  const Point& point = math::integratePosition<ConfigSpaceT>(
1396  math::toManifoldPoint<ConfigSpaceT>(getPositionsStatic()),
1397  getVelocitiesStatic(), dt);
1398 
1399  setPositionsStatic(math::toEuclideanPoint<ConfigSpaceT>(point));
1400 }
1401 
1402 //==============================================================================
1403 template <class ConfigSpaceT>
1405 {
1406  setVelocitiesStatic(math::integrateVelocity<ConfigSpaceT>(
1407  getVelocitiesStatic(),
1408  getAccelerationsStatic(), dt));
1409 }
1410 
1411 //==============================================================================
1412 template <class ConfigSpaceT>
1414  const Eigen::VectorXd& q2, const Eigen::VectorXd& q1) const
1415 {
1416  if (static_cast<size_t>(q1.size()) != getNumDofs()
1417  || static_cast<size_t>(q2.size()) != getNumDofs())
1418  {
1419  dterr << "[GenericJoint::getPositionsDifference] q1's size [" << q1.size()
1420  << "] or q2's size [" << q2.size() << "] must both equal the dof ["
1421  << this->getNumDofs() << "] for Joint [" << this->getName() << "].\n";
1422  assert(false);
1423  return Eigen::VectorXd::Zero(getNumDofs());
1424  }
1425 
1426  return getPositionDifferencesStatic(q2, q1);
1427 }
1428 
1429 //==============================================================================
1430 template <class ConfigSpaceT>
1431 typename ConfigSpaceT::Vector
1433  const Vector& q2, const Vector& q1) const
1434 {
1435  return q2 - q1;
1436  // TODO(JS): Move this implementation to each configuration space classes.
1437 }
1438 
1439 //==============================================================================
1440 template <class ConfigSpaceT>
1442 {
1443  if (index >= getNumDofs())
1444  {
1445  GenericJoint_REPORT_OUT_OF_RANGE(setSpringStiffness, index);
1446  return;
1447  }
1448 
1449  assert(k >= 0.0);
1450 
1451  GenericJoint_SET_IF_DIFFERENT( mSpringStiffnesses[index], k );
1452 }
1453 
1454 //==============================================================================
1455 template <class ConfigSpaceT>
1457 {
1458  if (index >= getNumDofs())
1459  {
1460  GenericJoint_REPORT_OUT_OF_RANGE(getSpringStiffness, index);
1461  return 0.0;
1462  }
1463 
1464  return Base::mAspectProperties.mSpringStiffnesses[index];
1465 }
1466 
1467 //==============================================================================
1468 template <class ConfigSpaceT>
1470 {
1471  if (index >= getNumDofs())
1472  {
1473  GenericJoint_REPORT_OUT_OF_RANGE(setRestPosition, index);
1474  return;
1475  }
1476 
1477  if (Base::mAspectProperties.mPositionLowerLimits[index] > q0
1478  || Base::mAspectProperties.mPositionUpperLimits[index] < q0)
1479  {
1480  dtwarn << "[GenericJoint::setRestPosition] Value of _q0 [" << q0
1481  << "], is out of the limit range ["
1482  << Base::mAspectProperties.mPositionLowerLimits[index] << ", "
1483  << Base::mAspectProperties.mPositionUpperLimits[index]
1484  << "] for index [" << index << "] of Joint [" << this->getName()
1485  << "].\n";
1486  return;
1487  }
1488 
1489  GenericJoint_SET_IF_DIFFERENT( mRestPositions[index], q0 );
1490 }
1491 
1492 //==============================================================================
1493 template <class ConfigSpaceT>
1495 {
1496  if (index >= getNumDofs())
1497  {
1498  GenericJoint_REPORT_OUT_OF_RANGE(getRestPosition, index);
1499  return 0.0;
1500  }
1501 
1502  return Base::mAspectProperties.mRestPositions[index];
1503 }
1504 
1505 //==============================================================================
1506 template <class ConfigSpaceT>
1508  double d)
1509 {
1510  if (index >= getNumDofs())
1511  {
1512  GenericJoint_REPORT_OUT_OF_RANGE(setDampingCoefficient, index);
1513  return;
1514  }
1515 
1516  assert(d >= 0.0);
1517 
1518  GenericJoint_SET_IF_DIFFERENT( mDampingCoefficients[index], d );
1519 }
1520 
1521 //==============================================================================
1522 template <class ConfigSpaceT>
1524 {
1525  if (index >= getNumDofs())
1526  {
1527  GenericJoint_REPORT_OUT_OF_RANGE(getDampingCoefficient, index);
1528  return 0.0;
1529  }
1530 
1531  return Base::mAspectProperties.mDampingCoefficients[index];
1532 }
1533 
1534 //==============================================================================
1535 template <class ConfigSpaceT>
1537  size_t index, double friction)
1538 {
1539  if (index >= getNumDofs())
1540  {
1541  GenericJoint_REPORT_OUT_OF_RANGE(setCoulombFriction, index);
1542  return;
1543  }
1544 
1545  assert(friction >= 0.0);
1546 
1548 }
1549 
1550 //==============================================================================
1551 template <class ConfigSpaceT>
1553 {
1554  if (index >= getNumDofs())
1555  {
1556  GenericJoint_REPORT_OUT_OF_RANGE(getCoulombFriction, index);
1557  return 0.0;
1558  }
1559 
1560  return Base::mAspectProperties.mFrictions[index];
1561 }
1562 
1563 //==============================================================================
1564 template <class ConfigSpaceT>
1566 {
1567  // Spring energy
1568  Vector displacement
1569  = getPositionsStatic() - Base::mAspectProperties.mRestPositions;
1570 
1571  const double pe = 0.5 * displacement.dot(
1572  Base::mAspectProperties.mSpringStiffnesses.cwiseProduct(displacement));
1573 
1574  return pe;
1575 }
1576 
1577 //==============================================================================
1578 template <class ConfigSpaceT>
1579 const math::Jacobian
1581 {
1582  return getRelativeJacobianStatic();
1583 }
1584 
1585 //==============================================================================
1586 template <class ConfigSpaceT>
1589 {
1590  if (this->mIsRelativeJacobianDirty)
1591  {
1592  this->updateRelativeJacobian(false);
1593  this->mIsRelativeJacobianDirty = false;
1594  }
1595 
1596  return mJacobian;
1597 }
1598 
1599 //==============================================================================
1600 template <class ConfigSpaceT>
1602  const Eigen::VectorXd& positions) const
1603 {
1604  return getRelativeJacobianStatic(positions);
1605 }
1606 
1607 //==============================================================================
1608 template <class ConfigSpaceT>
1609 const math::Jacobian
1611 {
1612  return getRelativeJacobianTimeDerivStatic();
1613 }
1614 
1615 //==============================================================================
1616 template <class ConfigSpaceT>
1619 {
1620  if (this->mIsRelativeJacobianTimeDerivDirty)
1621  {
1622  this->updateRelativeJacobianTimeDeriv();
1623  this->mIsRelativeJacobianTimeDerivDirty = false;
1624  }
1625 
1626  return mJacobianDeriv;
1627 }
1628 
1629 //==============================================================================
1630 template <class ConfigSpaceT>
1632  const Properties& properties)
1633  : mVelocityChanges(Vector::Zero()),
1634  mImpulses(Vector::Zero()),
1635  mConstraintImpulses(Vector::Zero()),
1636  mJacobian(JacobianMatrix::Zero()),
1637  mJacobianDeriv(JacobianMatrix::Zero()),
1638  mInvProjArtInertia(Matrix::Zero()),
1639  mInvProjArtInertiaImplicit(Matrix::Zero()),
1640  mTotalForce(Vector::Zero()),
1641  mTotalImpulse(Vector::Zero())
1642 {
1643  for (auto i = 0u; i < NumDofs; ++i)
1644  mDofs[i] = this->createDofPointer(i);
1645 
1646  // Joint and GenericJoint Aspects must be created by the most derived class.
1647  this->mAspectState.mPositions = properties.mInitialPositions;
1648  this->mAspectState.mVelocities = properties.mInitialVelocities;
1649 }
1650 
1651 //==============================================================================
1652 template <class ConfigSpaceT>
1654 {
1655  const SkeletonPtr& skel = this->mChildBodyNode->getSkeleton();
1656  for (auto i = 0u; i < NumDofs; ++i)
1657  {
1658  Base::mAspectProperties.mDofNames[i]
1659  = skel->mNameMgrForDofs.issueNewNameAndAdd(mDofs[i]->getName(),
1660  mDofs[i]);
1661  }
1662 }
1663 
1664 //==============================================================================
1665 template <class ConfigSpaceT>
1668 {
1669  assert(this->mChildBodyNode);
1670  return this->mChildBodyNode->getBodyForce()
1671  - this->getRelativeJacobianStatic() * this->mAspectState.mForces;
1672 }
1673 
1674 //==============================================================================
1675 template <class ConfigSpaceT>
1677 {
1678  this->mSpatialVelocity =
1679  this->getRelativeJacobianStatic() * this->getVelocitiesStatic();
1680 }
1681 
1682 //==============================================================================
1683 template <class ConfigSpaceT>
1685 {
1686  this->mSpatialAcceleration =
1687  this->getRelativePrimaryAcceleration()
1688  + this->getRelativeJacobianTimeDerivStatic() * this->getVelocitiesStatic();
1689 }
1690 
1691 //==============================================================================
1692 template <class ConfigSpaceT>
1694 {
1695  this->mPrimaryAcceleration =
1696  this->getRelativeJacobianStatic() * this->getAccelerationsStatic();
1697 }
1698 
1699 //==============================================================================
1700 template <class ConfigSpaceT>
1702 {
1703  // Add joint velocity to _vel
1704  vel.noalias() += getRelativeJacobianStatic() * getVelocitiesStatic();
1705 
1706  // Verification
1707  assert(!math::isNan(vel));
1708 }
1709 
1710 //==============================================================================
1711 template <class ConfigSpaceT>
1713  Eigen::Vector6d& partialAcceleration,
1714  const Eigen::Vector6d& childVelocity)
1715 {
1716  // ad(V, S * dq) + dS * dq
1717  partialAcceleration = math::ad(childVelocity,
1718  getRelativeJacobianStatic() * getVelocitiesStatic())
1719  + getRelativeJacobianTimeDerivStatic() * getVelocitiesStatic();
1720  // Verification
1721  assert(!math::isNan(partialAcceleration));
1722 }
1723 
1724 //==============================================================================
1725 template <class ConfigSpaceT>
1727  Eigen::Vector6d& acc)
1728 {
1729  // Add joint acceleration to _acc
1730  acc.noalias() += getRelativeJacobianStatic() * getAccelerationsStatic();
1731 
1732  // Verification
1733  assert(!math::isNan(acc));
1734 }
1735 
1736 //==============================================================================
1737 template <class ConfigSpaceT>
1739  Eigen::Vector6d& velocityChange)
1740 {
1741  // Add joint velocity change to velocityChange
1742  velocityChange.noalias() += getRelativeJacobianStatic() * mVelocityChanges;
1743 
1744  // Verification
1745  assert(!math::isNan(velocityChange));
1746 }
1747 
1748 //==============================================================================
1749 template <class ConfigSpaceT>
1750 const typename GenericJoint<ConfigSpaceT>::Matrix&
1752 {
1754 
1755  return mInvProjArtInertia;
1756 }
1757 
1758 //==============================================================================
1759 template <class ConfigSpaceT>
1760 const typename GenericJoint<ConfigSpaceT>::Matrix&
1762 {
1764 
1765  return mInvProjArtInertiaImplicit;
1766 }
1767 
1768 //==============================================================================
1769 template <class ConfigSpaceT>
1771  Eigen::Matrix6d& parentArtInertia,
1772  const Eigen::Matrix6d& childArtInertia)
1773 {
1774  switch (Joint::mAspectProperties.mActuatorType)
1775  {
1776  case Joint::FORCE:
1777  case Joint::PASSIVE:
1778  case Joint::SERVO:
1779  case Joint::MIMIC:
1780  addChildArtInertiaToDynamic(parentArtInertia,
1781  childArtInertia);
1782  break;
1783  case Joint::ACCELERATION:
1784  case Joint::VELOCITY:
1785  case Joint::LOCKED:
1786  addChildArtInertiaToKinematic(parentArtInertia,
1787  childArtInertia);
1788  break;
1789  default:
1790  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(addChildArtInertiaTo);
1791  break;
1792  }
1793 }
1794 
1795 //==============================================================================
1796 template <class ConfigSpaceT>
1798  Eigen::Matrix6d& parentArtInertia,
1799  const Eigen::Matrix6d& childArtInertia)
1800 {
1801  // Child body's articulated inertia
1802  JacobianMatrix AIS = childArtInertia * getRelativeJacobianStatic();
1803  Eigen::Matrix6d PI = childArtInertia;
1804  PI.noalias() -= AIS * mInvProjArtInertia * AIS.transpose();
1805  assert(!math::isNan(PI));
1806 
1807  // Add child body's articulated inertia to parent body's articulated inertia.
1808  // Note that mT should be updated.
1809  parentArtInertia += math::transformInertia(
1810  this->getRelativeTransform().inverse(), PI);
1811 }
1812 
1813 //==============================================================================
1814 template <class ConfigSpaceT>
1816  Eigen::Matrix6d& parentArtInertia,
1817  const Eigen::Matrix6d& childArtInertia)
1818 {
1819  // Add child body's articulated inertia to parent body's articulated inertia.
1820  // Note that mT should be updated.
1821  parentArtInertia += math::transformInertia(
1822  this->getRelativeTransform().inverse(), childArtInertia);
1823 }
1824 
1825 //==============================================================================
1826 template <class ConfigSpaceT>
1828  Eigen::Matrix6d& parentArtInertia,
1829  const Eigen::Matrix6d& childArtInertia)
1830 {
1831  switch (Joint::mAspectProperties.mActuatorType)
1832  {
1833  case Joint::FORCE:
1834  case Joint::PASSIVE:
1835  case Joint::SERVO:
1836  case Joint::MIMIC:
1837  addChildArtInertiaImplicitToDynamic(parentArtInertia,
1838  childArtInertia);
1839  break;
1840  case Joint::ACCELERATION:
1841  case Joint::VELOCITY:
1842  case Joint::LOCKED:
1843  addChildArtInertiaImplicitToKinematic(parentArtInertia,
1844  childArtInertia);
1845  break;
1846  default:
1847  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(addChildArtInertiaImplicitTo);
1848  break;
1849  }
1850 }
1851 
1852 //==============================================================================
1853 template <class ConfigSpaceT>
1855  Eigen::Matrix6d& parentArtInertia,
1856  const Eigen::Matrix6d& childArtInertia)
1857 {
1858  // Child body's articulated inertia
1859  JacobianMatrix AIS = childArtInertia * getRelativeJacobianStatic();
1860  Eigen::Matrix6d PI = childArtInertia;
1861  PI.noalias() -= AIS * mInvProjArtInertiaImplicit * AIS.transpose();
1862  assert(!math::isNan(PI));
1863 
1864  // Add child body's articulated inertia to parent body's articulated inertia.
1865  // Note that mT should be updated.
1866  parentArtInertia += math::transformInertia(
1867  this->getRelativeTransform().inverse(), PI);
1868 }
1869 
1870 //==============================================================================
1871 template <class ConfigSpaceT>
1873  Eigen::Matrix6d& parentArtInertia,
1874  const Eigen::Matrix6d& childArtInertia)
1875 {
1876  // Add child body's articulated inertia to parent body's articulated inertia.
1877  // Note that mT should be updated.
1878  parentArtInertia += math::transformInertia(
1879  this->getRelativeTransform().inverse(), childArtInertia);
1880 }
1881 
1882 //==============================================================================
1883 template <class ConfigSpaceT>
1885  const Eigen::Matrix6d& artInertia)
1886 {
1887  switch (Joint::mAspectProperties.mActuatorType)
1888  {
1889  case Joint::FORCE:
1890  case Joint::PASSIVE:
1891  case Joint::SERVO:
1892  case Joint::MIMIC:
1893  updateInvProjArtInertiaDynamic(artInertia);
1894  break;
1895  case Joint::ACCELERATION:
1896  case Joint::VELOCITY:
1897  case Joint::LOCKED:
1898  updateInvProjArtInertiaKinematic(artInertia);
1899  break;
1900  default:
1901  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(updateInvProjArtInertia);
1902  break;
1903  }
1904 }
1905 
1906 //==============================================================================
1907 template <class ConfigSpaceT>
1909  const Eigen::Matrix6d& artInertia)
1910 {
1911  // Projected articulated inertia
1912  const JacobianMatrix& Jacobian = getRelativeJacobianStatic();
1913  const Matrix projAI = Jacobian.transpose() * artInertia * Jacobian;
1914 
1915  // Inversion of projected articulated inertia
1916  mInvProjArtInertia = math::inverse<ConfigSpaceT>(projAI);
1917 
1918  // Verification
1919  assert(!math::isNan(mInvProjArtInertia));
1920 }
1921 
1922 //==============================================================================
1923 template <class ConfigSpaceT>
1925  const Eigen::Matrix6d& /*_artInertia*/)
1926 {
1927  // Do nothing
1928 }
1929 
1930 //==============================================================================
1931 template <class ConfigSpaceT>
1933  const Eigen::Matrix6d& artInertia,
1934  double timeStep)
1935 {
1936  switch (Joint::mAspectProperties.mActuatorType)
1937  {
1938  case Joint::FORCE:
1939  case Joint::PASSIVE:
1940  case Joint::SERVO:
1941  case Joint::MIMIC:
1942  updateInvProjArtInertiaImplicitDynamic(artInertia, timeStep);
1943  break;
1944  case Joint::ACCELERATION:
1945  case Joint::VELOCITY:
1946  case Joint::LOCKED:
1947  updateInvProjArtInertiaImplicitKinematic(artInertia, timeStep);
1948  break;
1949  default:
1951  updateInvProjArtInertiaImplicit);
1952  break;
1953  }
1954 }
1955 
1956 //==============================================================================
1957 template <class ConfigSpaceT>
1959  const Eigen::Matrix6d& artInertia,
1960  double timeStep)
1961 {
1962  // Projected articulated inertia
1963  const JacobianMatrix& Jacobian = getRelativeJacobianStatic();
1964  Matrix projAI = Jacobian.transpose() * artInertia * Jacobian;
1965 
1966  // Add additional inertia for implicit damping and spring force
1967  projAI +=
1968  (timeStep * Base::mAspectProperties.mDampingCoefficients
1969  + timeStep * timeStep * Base::mAspectProperties.mSpringStiffnesses).asDiagonal();
1970 
1971  // Inversion of projected articulated inertia
1972  mInvProjArtInertiaImplicit = math::inverse<ConfigSpaceT>(projAI);
1973 
1974  // Verification
1975  assert(!math::isNan(mInvProjArtInertiaImplicit));
1976 }
1977 
1978 //==============================================================================
1979 template <class ConfigSpaceT>
1981  const Eigen::Matrix6d& /*artInertia*/, double /*timeStep*/)
1982 {
1983  // Do nothing
1984 }
1985 
1986 //==============================================================================
1987 template <class ConfigSpaceT>
1989  Eigen::Vector6d& parentBiasForce,
1990  const Eigen::Matrix6d& childArtInertia,
1991  const Eigen::Vector6d& childBiasForce,
1992  const Eigen::Vector6d& childPartialAcc)
1993 {
1994  switch (Joint::mAspectProperties.mActuatorType)
1995  {
1996  case Joint::FORCE:
1997  case Joint::PASSIVE:
1998  case Joint::SERVO:
1999  case Joint::MIMIC:
2000  addChildBiasForceToDynamic(parentBiasForce,
2001  childArtInertia,
2002  childBiasForce,
2003  childPartialAcc);
2004  break;
2005  case Joint::ACCELERATION:
2006  case Joint::VELOCITY:
2007  case Joint::LOCKED:
2008  addChildBiasForceToKinematic(parentBiasForce,
2009  childArtInertia,
2010  childBiasForce,
2011  childPartialAcc);
2012  break;
2013  default:
2014  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(addChildBiasForceTo);
2015  break;
2016  }
2017 }
2018 
2019 //==============================================================================
2020 template <class ConfigSpaceT>
2022  Eigen::Vector6d& parentBiasForce,
2023  const Eigen::Matrix6d& childArtInertia,
2024  const Eigen::Vector6d& childBiasForce,
2025  const Eigen::Vector6d& childPartialAcc)
2026 {
2027  // Compute beta
2028  const Eigen::Vector6d beta
2029  = childBiasForce
2030  + childArtInertia
2031  * (childPartialAcc
2032  + getRelativeJacobianStatic() * getInvProjArtInertiaImplicit()
2033  *mTotalForce);
2034 
2035  // Eigen::Vector6d beta
2036  // = _childBiasForce;
2037  // beta.noalias() += _childArtInertia * _childPartialAcc;
2038  // beta.noalias() += _childArtInertia * mJacobian * getInvProjArtInertiaImplicit() * mTotalForce;
2039 
2040  // Verification
2041  assert(!math::isNan(beta));
2042 
2043  // Add child body's bias force to parent body's bias force. Note that mT
2044  // should be updated.
2045  parentBiasForce += math::dAdInvT(this->getRelativeTransform(), beta);
2046 }
2047 
2048 //==============================================================================
2049 template <class ConfigSpaceT>
2051  Eigen::Vector6d& _parentBiasForce,
2052  const Eigen::Matrix6d& childArtInertia,
2053  const Eigen::Vector6d& childBiasForce,
2054  const Eigen::Vector6d& childPartialAcc)
2055 {
2056  // Compute beta
2057  const Eigen::Vector6d beta
2058  = childBiasForce
2059  + childArtInertia*(childPartialAcc
2060  + getRelativeJacobianStatic()*getAccelerationsStatic());
2061 
2062  // Eigen::Vector6d beta
2063  // = _childBiasForce;
2064  // beta.noalias() += _childArtInertia * _childPartialAcc;
2065  // beta.noalias() += _childArtInertia * mJacobian * getInvProjArtInertiaImplicit() * mTotalForce;
2066 
2067  // Verification
2068  assert(!math::isNan(beta));
2069 
2070  // Add child body's bias force to parent body's bias force. Note that mT
2071  // should be updated.
2072  _parentBiasForce += math::dAdInvT(this->getRelativeTransform(), beta);
2073 }
2074 
2075 //==============================================================================
2076 template <class ConfigSpaceT>
2078  Eigen::Vector6d& parentBiasImpulse,
2079  const Eigen::Matrix6d& childArtInertia,
2080  const Eigen::Vector6d& childBiasImpulse)
2081 {
2082  switch (Joint::mAspectProperties.mActuatorType)
2083  {
2084  case Joint::FORCE:
2085  case Joint::PASSIVE:
2086  case Joint::SERVO:
2087  case Joint::MIMIC:
2088  addChildBiasImpulseToDynamic(parentBiasImpulse,
2089  childArtInertia,
2090  childBiasImpulse);
2091  break;
2092  case Joint::ACCELERATION:
2093  case Joint::VELOCITY:
2094  case Joint::LOCKED:
2095  addChildBiasImpulseToKinematic(parentBiasImpulse,
2096  childArtInertia,
2097  childBiasImpulse);
2098  break;
2099  default:
2100  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(addChildBiasImpulseTo);
2101  break;
2102  }
2103 }
2104 
2105 //==============================================================================
2106 template <class ConfigSpaceT>
2108  Eigen::Vector6d& _parentBiasImpulse,
2109  const Eigen::Matrix6d& childArtInertia,
2110  const Eigen::Vector6d& childBiasImpulse)
2111 {
2112  // Compute beta
2113  const Eigen::Vector6d beta
2114  = childBiasImpulse
2115  + childArtInertia*getRelativeJacobianStatic()
2116  *getInvProjArtInertia()*mTotalImpulse;
2117 
2118  // Verification
2119  assert(!math::isNan(beta));
2120 
2121  // Add child body's bias force to parent body's bias force. Note that mT
2122  // should be updated.
2123  _parentBiasImpulse += math::dAdInvT(this->getRelativeTransform(), beta);
2124 }
2125 
2126 //==============================================================================
2127 template <class ConfigSpaceT>
2129  Eigen::Vector6d& parentBiasImpulse,
2130  const Eigen::Matrix6d& /*childArtInertia*/,
2131  const Eigen::Vector6d& childBiasImpulse)
2132 {
2133  // Add child body's bias force to parent body's bias force. Note that mT
2134  // should be updated.
2135  parentBiasImpulse += math::dAdInvT(this->getRelativeTransform(), childBiasImpulse);
2136 }
2137 
2138 //==============================================================================
2139 template <class ConfigSpaceT>
2141  const Eigen::Vector6d& bodyForce,
2142  double timeStep)
2143 {
2144  assert(timeStep > 0.0);
2145 
2146  switch (Joint::mAspectProperties.mActuatorType)
2147  {
2148  case Joint::FORCE:
2149  this->mAspectState.mForces = this->mAspectState.mCommands;
2150  updateTotalForceDynamic(bodyForce, timeStep);
2151  break;
2152  case Joint::PASSIVE:
2153  case Joint::SERVO:
2154  case Joint::MIMIC:
2155  this->mAspectState.mForces.setZero();
2156  updateTotalForceDynamic(bodyForce, timeStep);
2157  break;
2158  case Joint::ACCELERATION:
2159  setAccelerationsStatic(this->mAspectState.mCommands);
2160  updateTotalForceKinematic(bodyForce, timeStep);
2161  break;
2162  case Joint::VELOCITY:
2163  setAccelerationsStatic(
2164  (this->mAspectState.mCommands - getVelocitiesStatic()) / timeStep );
2165  updateTotalForceKinematic(bodyForce, timeStep);
2166  break;
2167  case Joint::LOCKED:
2168  setVelocitiesStatic(Vector::Zero());
2169  setAccelerationsStatic(Vector::Zero());
2170  updateTotalForceKinematic(bodyForce, timeStep);
2171  break;
2172  default:
2173  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(updateTotalForce);
2174  break;
2175  }
2176 }
2177 
2178 //==============================================================================
2179 template <class ConfigSpaceT>
2181  const Eigen::Vector6d& bodyForce,
2182  double timeStep)
2183 {
2184  // Spring force
2185  const Vector springForce
2186  = -Base::mAspectProperties.mSpringStiffnesses.cwiseProduct(
2187  getPositionsStatic()
2188  - Base::mAspectProperties.mRestPositions
2189  + getVelocitiesStatic() * timeStep);
2190 
2191  // Damping force
2192  const Vector dampingForce
2193  = -Base::mAspectProperties.mDampingCoefficients.cwiseProduct(
2194  getVelocitiesStatic());
2195 
2196  //
2197  mTotalForce = this->mAspectState.mForces
2198  + springForce
2199  + dampingForce
2200  - getRelativeJacobianStatic().transpose() * bodyForce;
2201 }
2202 
2203 //==============================================================================
2204 template <class ConfigSpaceT>
2206  const Eigen::Vector6d& /*bodyForce*/,
2207  double /*timeStep*/)
2208 {
2209  // Do nothing
2210 }
2211 
2212 //==============================================================================
2213 template <class ConfigSpaceT>
2215  const Eigen::Vector6d& bodyImpulse)
2216 {
2217  switch (Joint::mAspectProperties.mActuatorType)
2218  {
2219  case Joint::FORCE:
2220  case Joint::PASSIVE:
2221  case Joint::SERVO:
2222  case Joint::MIMIC:
2223  updateTotalImpulseDynamic(bodyImpulse);
2224  break;
2225  case Joint::ACCELERATION:
2226  case Joint::VELOCITY:
2227  case Joint::LOCKED:
2228  updateTotalImpulseKinematic(bodyImpulse);
2229  break;
2230  default:
2231  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(updateTotalImpulse);
2232  break;
2233  }
2234 }
2235 
2236 //==============================================================================
2237 template <class ConfigSpaceT>
2239  const Eigen::Vector6d& bodyImpulse)
2240 {
2241  //
2242  mTotalImpulse = mConstraintImpulses
2243  - getRelativeJacobianStatic().transpose() * bodyImpulse;
2244 }
2245 
2246 //==============================================================================
2247 template <class ConfigSpaceT>
2249  const Eigen::Vector6d& /*bodyImpulse*/)
2250 {
2251  // Do nothing
2252 }
2253 
2254 //==============================================================================
2255 template <class ConfigSpaceT>
2257 {
2258  mTotalImpulse.setZero();
2259 }
2260 
2261 //==============================================================================
2262 template <class ConfigSpaceT>
2264  const Eigen::Matrix6d& artInertia,
2265  const Eigen::Vector6d& spatialAcc)
2266 {
2267  switch (Joint::mAspectProperties.mActuatorType)
2268  {
2269  case Joint::FORCE:
2270  case Joint::PASSIVE:
2271  case Joint::SERVO:
2272  case Joint::MIMIC:
2273  updateAccelerationDynamic(artInertia, spatialAcc);
2274  break;
2275  case Joint::ACCELERATION:
2276  case Joint::VELOCITY:
2277  case Joint::LOCKED:
2278  updateAccelerationKinematic(artInertia, spatialAcc);
2279  break;
2280  default:
2281  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(updateAcceleration);
2282  break;
2283  }
2284 }
2285 
2286 //==============================================================================
2287 template <class ConfigSpaceT>
2289  const Eigen::Matrix6d& artInertia,
2290  const Eigen::Vector6d& spatialAcc)
2291 {
2292  //
2293  setAccelerationsStatic( getInvProjArtInertiaImplicit()
2294  * (mTotalForce - getRelativeJacobianStatic().transpose()
2295  *artInertia*math::AdInvT(this->getRelativeTransform(), spatialAcc)) );
2296 
2297  // Verification
2298  assert(!math::isNan(getAccelerationsStatic()));
2299 }
2300 
2301 //==============================================================================
2302 template <class ConfigSpaceT>
2304  const Eigen::Matrix6d& /*artInertia*/,
2305  const Eigen::Vector6d& /*spatialAcc*/)
2306 {
2307  // Do nothing
2308 }
2309 
2310 //==============================================================================
2311 template <class ConfigSpaceT>
2313  const Eigen::Matrix6d& artInertia,
2314  const Eigen::Vector6d& velocityChange)
2315 {
2316  switch (Joint::mAspectProperties.mActuatorType)
2317  {
2318  case Joint::FORCE:
2319  case Joint::PASSIVE:
2320  case Joint::SERVO:
2321  case Joint::MIMIC:
2322  updateVelocityChangeDynamic(artInertia, velocityChange);
2323  break;
2324  case Joint::ACCELERATION:
2325  case Joint::VELOCITY:
2326  case Joint::LOCKED:
2327  updateVelocityChangeKinematic(artInertia, velocityChange);
2328  break;
2329  default:
2330  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(updateVelocityChange);
2331  break;
2332  }
2333 }
2334 
2335 //==============================================================================
2336 template <class ConfigSpaceT>
2338  const Eigen::Matrix6d& artInertia,
2339  const Eigen::Vector6d& velocityChange)
2340 {
2341  //
2342  mVelocityChanges
2343  = getInvProjArtInertia()
2344  * (mTotalImpulse - getRelativeJacobianStatic().transpose()
2345  *artInertia*math::AdInvT(this->getRelativeTransform(), velocityChange));
2346 
2347  // Verification
2348  assert(!math::isNan(mVelocityChanges));
2349 }
2350 
2351 //==============================================================================
2352 template <class ConfigSpaceT>
2354  const Eigen::Matrix6d& /*artInertia*/,
2355  const Eigen::Vector6d& /*velocityChange*/)
2356 {
2357  // Do nothing
2358 }
2359 
2360 //==============================================================================
2361 template <class ConfigSpaceT>
2363  const Eigen::Vector6d& bodyForce,
2364  double timeStep,
2365  bool withDampingForces,
2366  bool withSpringForces)
2367 {
2368  this->mAspectState.mForces = getRelativeJacobianStatic().transpose() * bodyForce;
2369 
2370  // Damping force
2371  if (withDampingForces)
2372  {
2373  const typename ConfigSpaceT::Vector dampingForces
2374  = -Base::mAspectProperties.mDampingCoefficients.cwiseProduct(
2375  getVelocitiesStatic());
2376  this->mAspectState.mForces -= dampingForces;
2377  }
2378 
2379  // Spring force
2380  if (withSpringForces)
2381  {
2382  const typename ConfigSpaceT::Vector springForces
2383  = -Base::mAspectProperties.mSpringStiffnesses.cwiseProduct(
2384  getPositionsStatic()
2385  - Base::mAspectProperties.mRestPositions
2386  + getVelocitiesStatic() * timeStep);
2387  this->mAspectState.mForces -= springForces;
2388  }
2389 }
2390 
2391 //==============================================================================
2392 template <class ConfigSpaceT>
2394  const Eigen::Vector6d& bodyForce,
2395  double timeStep,
2396  bool withDampingForces,
2397  bool withSpringForces)
2398 {
2399  switch (Joint::mAspectProperties.mActuatorType)
2400  {
2401  case Joint::FORCE:
2402  case Joint::PASSIVE:
2403  case Joint::SERVO:
2404  case Joint::MIMIC:
2405  break;
2406  case Joint::ACCELERATION:
2407  case Joint::VELOCITY:
2408  case Joint::LOCKED:
2409  updateForceID(bodyForce, timeStep, withDampingForces, withSpringForces);
2410  break;
2411  default:
2413  break;
2414  }
2415 }
2416 
2417 //==============================================================================
2418 template <class ConfigSpaceT>
2420  const Eigen::Vector6d& bodyImpulse)
2421 {
2422  mImpulses = getRelativeJacobianStatic().transpose()*bodyImpulse;
2423 }
2424 
2425 //==============================================================================
2426 template <class ConfigSpaceT>
2428  const Eigen::Vector6d& bodyImpulse)
2429 {
2430  switch (Joint::mAspectProperties.mActuatorType)
2431  {
2432  case Joint::FORCE:
2433  case Joint::PASSIVE:
2434  case Joint::SERVO:
2435  case Joint::MIMIC:
2436  break;
2437  case Joint::ACCELERATION:
2438  case Joint::VELOCITY:
2439  case Joint::LOCKED:
2440  updateImpulseID(bodyImpulse);
2441  break;
2442  default:
2444  break;
2445  }
2446 }
2447 
2448 //==============================================================================
2449 template <class ConfigSpaceT>
2451 {
2452  switch (Joint::mAspectProperties.mActuatorType)
2453  {
2454  case Joint::FORCE:
2455  case Joint::PASSIVE:
2456  case Joint::SERVO:
2457  case Joint::MIMIC:
2458  updateConstrainedTermsDynamic(timeStep);
2459  break;
2460  case Joint::ACCELERATION:
2461  case Joint::VELOCITY:
2462  case Joint::LOCKED:
2463  updateConstrainedTermsKinematic(timeStep);
2464  break;
2465  default:
2466  GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(updateConstrainedTerms);
2467  break;
2468  }
2469 }
2470 
2471 //==============================================================================
2472 template <class ConfigSpaceT>
2474  double timeStep)
2475 {
2476  const double invTimeStep = 1.0 / timeStep;
2477 
2478  setVelocitiesStatic(getVelocitiesStatic() + mVelocityChanges);
2479  setAccelerationsStatic(getAccelerationsStatic()
2480  + mVelocityChanges * invTimeStep);
2481  this->mAspectState.mForces.noalias() += mImpulses * invTimeStep;
2482  // Note: As long as this is only called from BodyNode::updateConstrainedTerms
2483 }
2484 
2485 //==============================================================================
2486 template <class ConfigSpaceT>
2488  double timeStep)
2489 {
2490  this->mAspectState.mForces.noalias() += mImpulses / timeStep;
2491 }
2492 
2493 //==============================================================================
2494 template <class ConfigSpaceT>
2496  Eigen::Vector6d& parentBiasForce,
2497  const Eigen::Matrix6d& childArtInertia,
2498  const Eigen::Vector6d& childBiasForce)
2499 {
2500  // Compute beta
2501  Eigen::Vector6d beta = childBiasForce;
2502  beta.noalias() += childArtInertia * getRelativeJacobianStatic()
2503  * getInvProjArtInertia() * mInvM_a;
2504 
2505  // Verification
2506  assert(!math::isNan(beta));
2507 
2508  // Add child body's bias force to parent body's bias force. Note that mT
2509  // should be updated.
2510  parentBiasForce += math::dAdInvT(this->getRelativeTransform(), beta);
2511 }
2512 
2513 //==============================================================================
2514 template <class ConfigSpaceT>
2516  Eigen::Vector6d& parentBiasForce,
2517  const Eigen::Matrix6d& childArtInertia,
2518  const Eigen::Vector6d& childBiasForce)
2519 {
2520  // Compute beta
2521  Eigen::Vector6d beta = childBiasForce;
2522  beta.noalias() += childArtInertia * getRelativeJacobianStatic()
2523  * getInvProjArtInertiaImplicit() * mInvM_a;
2524 
2525  // Verification
2526  assert(!math::isNan(beta));
2527 
2528  // Add child body's bias force to parent body's bias force. Note that mT
2529  // should be updated.
2530  parentBiasForce += math::dAdInvT(this->getRelativeTransform(), beta);
2531 }
2532 
2533 //==============================================================================
2534 template <class ConfigSpaceT>
2536  const Eigen::Vector6d& bodyForce)
2537 {
2538  // Compute alpha
2539  mInvM_a = this->mAspectState.mForces
2540  - getRelativeJacobianStatic().transpose() * bodyForce;
2541 }
2542 
2543 //==============================================================================
2544 template <class ConfigSpaceT>
2546  Eigen::MatrixXd& _invMassMat,
2547  const size_t _col,
2548  const Eigen::Matrix6d& artInertia,
2549  const Eigen::Vector6d& spatialAcc)
2550 {
2551  //
2552  mInvMassMatrixSegment
2553  = getInvProjArtInertia()
2554  * (mInvM_a - getRelativeJacobianStatic().transpose()
2555  * artInertia * math::AdInvT(this->getRelativeTransform(), spatialAcc));
2556 
2557  // Verification
2558  assert(!math::isNan(mInvMassMatrixSegment));
2559 
2560  // Index
2561  size_t iStart = mDofs[0]->mIndexInTree;
2562 
2563  // Assign
2564  _invMassMat.block<NumDofs, 1>(iStart, _col) = mInvMassMatrixSegment;
2565 }
2566 
2567 //==============================================================================
2568 template <class ConfigSpaceT>
2570  Eigen::MatrixXd& invMassMat,
2571  const size_t col,
2572  const Eigen::Matrix6d& artInertia,
2573  const Eigen::Vector6d& spatialAcc)
2574 {
2575  //
2576  mInvMassMatrixSegment
2577  = getInvProjArtInertiaImplicit()
2578  * (mInvM_a - getRelativeJacobianStatic().transpose()
2579  * artInertia * math::AdInvT(this->getRelativeTransform(), spatialAcc));
2580 
2581  // Verification
2582  assert(!math::isNan(mInvMassMatrixSegment));
2583 
2584  // Index
2585  size_t iStart = mDofs[0]->mIndexInTree;
2586 
2587  // Assign
2588  invMassMat.block<NumDofs, 1>(iStart, col) = mInvMassMatrixSegment;
2589 }
2590 
2591 //==============================================================================
2592 template <class ConfigSpaceT>
2594  Eigen::Vector6d& acc)
2595 {
2596  //
2597  acc += getRelativeJacobianStatic() * mInvMassMatrixSegment;
2598 }
2599 
2600 //==============================================================================
2601 template <class ConfigSpaceT>
2603  const Eigen::Vector6d& spatial)
2604 {
2605  return getRelativeJacobianStatic().transpose() * spatial;
2606 }
2607 
2608 } // namespace dynamics
2609 } // namespace dart
2610 
2611 #endif // DART_DYNAMICS_DETAIL_GenericJoint_HPP_
#define dterr
Output an error message.
Definition: Console.hpp:49
#define dtwarn
Output a warning message.
Definition: Console.hpp:46
BodyPropPtr properties
Definition: SdfParser.cpp:80
std::string * name
Definition: SkelParser.cpp:1642
bool * preserveName
Definition: SkelParser.cpp:1641
Eigen::VectorXd velocity
Definition: SkelParser.cpp:108
Eigen::VectorXd force
Definition: SkelParser.cpp:110
std::size_t index
Definition: SkelParser.cpp:1617
Eigen::VectorXd acceleration
Definition: SkelParser.cpp:109
double * friction
Definition: SkelParser.cpp:1639
Eigen::VectorXd position
Definition: SkelParser.cpp:107
AspectProperties mAspectProperties
Aspect::Properties data, directly accessible to your derived class.
Definition: EmbeddedAspect.hpp:237
typename Impl::AspectState AspectState
Definition: EmbeddedAspect.hpp:444
AspectState mAspectState
Aspect::State data, directly accessible to your derived class.
Definition: EmbeddedAspect.hpp:422
typename Impl::AspectProperties AspectProperties
Definition: EmbeddedAspect.hpp:446
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition: DegreeOfFreedom.hpp:53
Definition: GenericJoint.hpp:49
void setAspectState(const AspectState &state)
Set the AspectState of this GenericJoint.
Definition: GenericJoint.hpp:114
void setForceLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition: GenericJoint.hpp:1246
double getCommand(std::size_t index) const override
Definition: GenericJoint.hpp:391
typename ConfigSpaceT::Matrix Matrix
Definition: GenericJoint.hpp:61
void addChildArtInertiaImplicitToKinematic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition: GenericJoint.hpp:1872
Eigen::VectorXd getCommands() const override
Definition: GenericJoint.hpp:473
void resetVelocities() override
Definition: GenericJoint.hpp:946
const Vector & getPositionsStatic() const
Fixed-size version of getPositions()
Definition: GenericJoint.hpp:732
void setAccelerationsStatic(const Vector &accels)
Fixed-size version of setAccelerations()
Definition: GenericJoint.hpp:759
void copy(const ThisClass &otherJoint)
Copy the Properties of another GenericJoint.
Definition: GenericJoint.hpp:159
void setForceUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition: GenericJoint.hpp:1294
void updateTotalImpulseKinematic(const Eigen::Vector6d &bodyImpulse)
Definition: GenericJoint.hpp:2248
void setCoulombFriction(std::size_t index, double friction) override
Definition: GenericJoint.hpp:1536
const JacobianMatrix & getRelativeJacobianTimeDerivStatic() const
Fixed-size version of getRelativeJacobianTimeDeriv()
Definition: GenericJoint.hpp:1618
void setRestPosition(std::size_t index, double q0) override
Definition: GenericJoint.hpp:1469
void setAccelerations(const Eigen::VectorXd &accelerations) override
Definition: GenericJoint.hpp:1036
void updateTotalImpulse(const Eigen::Vector6d &bodyImpulse) override
Definition: GenericJoint.hpp:2214
void updateForceFD(const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForcese, bool withSpringForces) override
Definition: GenericJoint.hpp:2393
const Matrix & getInvProjArtInertiaImplicit() const
Get the inverse of projected articulated inertia for implicit joint damping and spring forces.
Definition: GenericJoint.hpp:1761
Eigen::VectorXd getPositionUpperLimits() const override
Definition: GenericJoint.hpp:631
void setVelocityUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition: GenericJoint.hpp:912
void updateForceID(const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForces, bool withSpringForces) override
Definition: GenericJoint.hpp:2362
Eigen::VectorXd getAccelerationUpperLimits() const override
Definition: GenericJoint.hpp:1153
void updateAccelerationKinematic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc)
Definition: GenericJoint.hpp:2303
void updateVelocityChangeDynamic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange)
Definition: GenericJoint.hpp:2337
Eigen::VectorXd getVelocityLowerLimits() const override
Definition: GenericJoint.hpp:877
void updateInvProjArtInertiaImplicit(const Eigen::Matrix6d &artInertia, double timeStep) override
Definition: GenericJoint.hpp:1932
void setVelocityLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition: GenericJoint.hpp:863
void updateConstrainedTermsDynamic(double timeStep)
Definition: GenericJoint.hpp:2473
void setPositionLowerLimit(std::size_t index, double position) override
Definition: GenericJoint.hpp:542
const GenericJoint< ConfigSpaceT >::JacobianMatrix & getRelativeJacobianStatic() const
Fixed-size version of getRelativeJacobian()
Definition: GenericJoint.hpp:1588
void addChildArtInertiaToDynamic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition: GenericJoint.hpp:1797
const math::Jacobian getRelativeJacobianTimeDeriv() const override
Definition: GenericJoint.hpp:1610
void setVelocities(const Eigen::VectorXd &velocities) override
Definition: GenericJoint.hpp:812
void addChildBiasImpulseToKinematic(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse)
Definition: GenericJoint.hpp:2128
void addChildArtInertiaImplicitTo(Eigen::Matrix6d &parentArtInertiaImplicit, const Eigen::Matrix6d &childArtInertiaImplicit) override
Definition: GenericJoint.hpp:1827
void setPosition(std::size_t index, double position) override
Definition: GenericJoint.hpp:487
void updateVelocityChange(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange) override
Definition: GenericJoint.hpp:2312
void setCommand(std::size_t index, double command) override
Definition: GenericJoint.hpp:326
std::array< DegreeOfFreedom *, NumDofs > mDofs
Array of DegreeOfFreedom objects.
Definition: GenericJoint.hpp:675
void setInitialPosition(std::size_t index, double initial) override
Definition: GenericJoint.hpp:672
Eigen::VectorXd getForces() const override
Definition: GenericJoint.hpp:1212
void resetCommands() override
Definition: GenericJoint.hpp:480
void setVelocityChange(std::size_t index, double velocityChange) override
Definition: GenericJoint.hpp:1325
void setAccelerationUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition: GenericJoint.hpp:1139
void setPartialAccelerationTo(Eigen::Vector6d &partialAcceleration, const Eigen::Vector6d &childVelocity) override
Definition: GenericJoint.hpp:1712
double getVelocity(std::size_t index) const override
Definition: GenericJoint.hpp:799
Eigen::Vector6d getBodyConstraintWrench() const override
Definition: GenericJoint.hpp:1667
void addAccelerationTo(Eigen::Vector6d &acc) override
Definition: GenericJoint.hpp:1726
void updateTotalImpulseDynamic(const Eigen::Vector6d &bodyImpulse)
Definition: GenericJoint.hpp:2238
void setForce(std::size_t index, double force) override
Definition: GenericJoint.hpp:1167
void setInitialVelocity(std::size_t index, double initial) override
Definition: GenericJoint.hpp:953
double getForce(std::size_t index) const override
Definition: GenericJoint.hpp:1183
void setInitialVelocities(const Eigen::VectorXd &initial) override
Definition: GenericJoint.hpp:980
void updateInvProjArtInertiaDynamic(const Eigen::Matrix6d &artInertia)
Definition: GenericJoint.hpp:1908
DegreeOfFreedom * getDof(std::size_t index) override
void setPositionUpperLimit(std::size_t index, double position) override
Definition: GenericJoint.hpp:590
void updateInvProjArtInertiaImplicitKinematic(const Eigen::Matrix6d &artInertia, double timeStep)
Definition: GenericJoint.hpp:1980
const math::Jacobian getRelativeJacobian() const override
Definition: GenericJoint.hpp:1580
std::size_t getNumDofs() const override
Definition: GenericJoint.hpp:215
void resetForces() override
Definition: GenericJoint.hpp:1315
void addChildArtInertiaTo(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) override
Definition: GenericJoint.hpp:1770
Eigen::VectorXd getPositionLowerLimits() const override
Definition: GenericJoint.hpp:583
bool isDofNamePreserved(size_t index) const override
Definition: GenericJoint.hpp:269
void addVelocityTo(Eigen::Vector6d &vel) override
Definition: GenericJoint.hpp:1701
void preserveDofName(size_t index, bool preserve) override
Definition: GenericJoint.hpp:256
double getVelocityUpperLimit(std::size_t index) const override
Definition: GenericJoint.hpp:898
double getVelocityChange(std::size_t index) const override
Definition: GenericJoint.hpp:1339
void updateTotalForce(const Eigen::Vector6d &bodyForce, double timeStep) override
Definition: GenericJoint.hpp:2140
void resetConstraintImpulses() override
Definition: GenericJoint.hpp:1386
virtual Vector getPositionDifferencesStatic(const Vector &q2, const Vector &q1) const
Fixed-size version of getPositionDifferences()
Definition: GenericJoint.hpp:1432
void setVelocity(std::size_t index, double velocity) override
Definition: GenericJoint.hpp:778
double getRestPosition(std::size_t index) const override
Definition: GenericJoint.hpp:1494
void updateConstrainedTerms(double timeStep) override
Definition: GenericJoint.hpp:2450
void integrateVelocities(double dt) override
Definition: GenericJoint.hpp:1404
Eigen::VectorXd getPositions() const override
Definition: GenericJoint.hpp:535
void addChildBiasImpulseToDynamic(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse)
Definition: GenericJoint.hpp:2107
double getAcceleration(std::size_t index) const override
Definition: GenericJoint.hpp:1023
Eigen::VectorXd getVelocities() const override
Definition: GenericJoint.hpp:829
Eigen::VectorXd getInitialPositions() const override
Definition: GenericJoint.hpp:713
Eigen::VectorXd getPositionDifferences(const Eigen::VectorXd &q2, const Eigen::VectorXd &q1) const override
Definition: GenericJoint.hpp:1413
void setPositionLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition: GenericJoint.hpp:569
double getAccelerationUpperLimit(std::size_t index) const override
Definition: GenericJoint.hpp:1125
void setForceLowerLimit(size_t index, double force) override
Definition: GenericJoint.hpp:1219
void setSpringStiffness(std::size_t index, double k) override
Definition: GenericJoint.hpp:1441
void updateRelativePrimaryAcceleration() const override
Definition: GenericJoint.hpp:1693
void setProperties(const Properties &properties)
Set the Properties of this GenericJoint.
Definition: GenericJoint.hpp:98
double getForceLowerLimit(std::size_t index) const override
Definition: GenericJoint.hpp:1232
static constexpr std::size_t NumDofs
Definition: GenericJoint.hpp:52
const Vector & getVelocitiesStatic() const
Fixed-size version of getVelocities()
Definition: GenericJoint.hpp:752
double getPositionUpperLimit(std::size_t index) const override
Definition: GenericJoint.hpp:604
const std::string & getDofName(size_t index) const override
Definition: GenericJoint.hpp:282
ThisClass & operator=(const ThisClass &other)
Same as copy(const GenericJoint&)
Definition: GenericJoint.hpp:182
double computePotentialEnergy() const override
Definition: GenericJoint.hpp:1565
double getSpringStiffness(std::size_t index) const override
Definition: GenericJoint.hpp:1456
void setDampingCoefficient(std::size_t index, double coeff) override
Definition: GenericJoint.hpp:1507
void updateInvProjArtInertia(const Eigen::Matrix6d &artInertia) override
Definition: GenericJoint.hpp:1884
void resetVelocity(std::size_t index) override
Definition: GenericJoint.hpp:933
void setPositionsStatic(const Vector &positions)
Fixed-size version of setPositions()
Definition: GenericJoint.hpp:720
void addChildBiasForceForInvAugMassMatrix(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override
Definition: GenericJoint.hpp:2515
void updateConstrainedTermsKinematic(double timeStep)
Definition: GenericJoint.hpp:2487
void setAccelerationLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition: GenericJoint.hpp:1089
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this GenericJoint.
Definition: GenericJoint.hpp:125
Eigen::VectorXd getForceUpperLimits() const override
Definition: GenericJoint.hpp:1308
detail::GenericJointProperties< ConfigSpaceT > Properties
Definition: GenericJoint.hpp:64
void updateImpulseFD(const Eigen::Vector6d &bodyImpulse) override
Definition: GenericJoint.hpp:2427
GenericJoint(const ThisClass &)=delete
void updateInvProjArtInertiaImplicitDynamic(const Eigen::Matrix6d &artInertia, double timeStep)
Definition: GenericJoint.hpp:1958
void updateTotalForceKinematic(const Eigen::Vector6d &bodyForce, double timeStep)
Definition: GenericJoint.hpp:2205
void resetTotalImpulses() override
Definition: GenericJoint.hpp:2256
void integratePositions(double dt) override
Definition: GenericJoint.hpp:1393
void setPositions(const Eigen::VectorXd &positions) override
Definition: GenericJoint.hpp:521
void addChildBiasForceToDynamic(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc)
Definition: GenericJoint.hpp:2021
Eigen::VectorXd getForceLowerLimits() const override
Definition: GenericJoint.hpp:1260
double getInitialVelocity(std::size_t index) const override
Definition: GenericJoint.hpp:967
Eigen::VectorXd getAccelerations() const override
Definition: GenericJoint.hpp:1053
typename ConfigSpaceT::Vector Vector
Definition: GenericJoint.hpp:59
void updateVelocityChangeKinematic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange)
Definition: GenericJoint.hpp:2353
const Vector & getAccelerationsStatic() const
Fixed-size version of getAccelerations()
Definition: GenericJoint.hpp:771
Eigen::VectorXd getInitialVelocities() const override
Definition: GenericJoint.hpp:994
void setCommands(const Eigen::VectorXd &commands) override
Definition: GenericJoint.hpp:404
Eigen::VectorXd getSpatialToGeneralized(const Eigen::Vector6d &spatial) override
Definition: GenericJoint.hpp:2602
typename ConfigSpaceT::JacobianMatrix JacobianMatrix
Definition: GenericJoint.hpp:60
void getInvAugMassMatrixSegment(Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition: GenericJoint.hpp:2569
double getVelocityLowerLimit(std::size_t index) const override
Definition: GenericJoint.hpp:850
void updateImpulseID(const Eigen::Vector6d &bodyImpulse) override
Definition: GenericJoint.hpp:2419
void setVelocityLowerLimit(std::size_t index, double velocity) override
Definition: GenericJoint.hpp:836
double getInitialPosition(std::size_t index) const override
Definition: GenericJoint.hpp:686
void updateAcceleration(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition: GenericJoint.hpp:2263
void addChildBiasForceToKinematic(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc)
Definition: GenericJoint.hpp:2050
void setVelocityUpperLimit(std::size_t index, double velocity) override
Definition: GenericJoint.hpp:884
typename ConfigSpaceT::Point Point
Definition: GenericJoint.hpp:57
void updateInvProjArtInertiaKinematic(const Eigen::Matrix6d &artInertia)
Definition: GenericJoint.hpp:1924
bool hasPositionLimit(std::size_t index) const override
Definition: GenericJoint.hpp:638
void setInitialPositions(const Eigen::VectorXd &initial) override
Definition: GenericJoint.hpp:699
virtual ~GenericJoint()
Destructor.
Definition: GenericJoint.hpp:90
void addChildBiasForceTo(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc) override
Definition: GenericJoint.hpp:1988
double getCoulombFriction(std::size_t index) const override
Definition: GenericJoint.hpp:1552
void addInvMassMatrixSegmentTo(Eigen::Vector6d &acc) override
Definition: GenericJoint.hpp:2593
void setConstraintImpulse(std::size_t index, double impulse) override
Definition: GenericJoint.hpp:1359
void resetPosition(std::size_t index) override
Definition: GenericJoint.hpp:652
double getForceUpperLimit(size_t index) const override
Definition: GenericJoint.hpp:1280
void registerDofs() override
Definition: GenericJoint.hpp:1653
void addVelocityChangeTo(Eigen::Vector6d &velocityChange) override
Definition: GenericJoint.hpp:1738
const std::string & setDofName(std::size_t index, const std::string &name, bool preserveName=true) override
Definition: GenericJoint.hpp:222
void setAccelerationUpperLimit(std::size_t index, double acceleration) override
Definition: GenericJoint.hpp:1110
double getDampingCoefficient(std::size_t index) const override
Definition: GenericJoint.hpp:1523
void setPositionUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition: GenericJoint.hpp:617
Eigen::VectorXd getAccelerationLowerLimits() const override
Definition: GenericJoint.hpp:1103
void updateTotalForceDynamic(const Eigen::Vector6d &bodyForce, double timeStep)
Definition: GenericJoint.hpp:2180
void setVelocitiesStatic(const Vector &velocities)
Fixed-size version of setVelocities()
Definition: GenericJoint.hpp:739
void updateRelativeSpatialAcceleration() const override
Definition: GenericJoint.hpp:1684
void updateRelativeSpatialVelocity() const override
Definition: GenericJoint.hpp:1676
void setForceUpperLimit(size_t index, double force) override
Definition: GenericJoint.hpp:1267
size_t getIndexInTree(size_t index) const override
Definition: GenericJoint.hpp:313
Eigen::VectorXd getVelocityUpperLimits() const override
Definition: GenericJoint.hpp:926
void setAccelerationLowerLimit(size_t index, double acceleration) override
Definition: GenericJoint.hpp:1060
double getPosition(std::size_t index) const override
Definition: GenericJoint.hpp:508
void addChildArtInertiaImplicitToDynamic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition: GenericJoint.hpp:1854
double getAccelerationLowerLimit(std::size_t index) const override
Definition: GenericJoint.hpp:1075
void addChildBiasImpulseTo(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse) override
Definition: GenericJoint.hpp:2077
double getPositionLowerLimit(std::size_t index) const override
Definition: GenericJoint.hpp:556
void updateAccelerationDynamic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc)
Definition: GenericJoint.hpp:2288
void resetPositions() override
Definition: GenericJoint.hpp:665
void addChildBiasForceForInvMassMatrix(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override
Definition: GenericJoint.hpp:2495
void getInvMassMatrixSegment(Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition: GenericJoint.hpp:2545
Properties getGenericJointProperties() const
Get the Properties of this GenericJoint.
Definition: GenericJoint.hpp:151
const Matrix & getInvProjArtInertia() const
Get the inverse of the projected articulated inertia.
Definition: GenericJoint.hpp:1751
void setForces(const Eigen::VectorXd &forces) override
Definition: GenericJoint.hpp:1196
void updateTotalForceForInvMassMatrix(const Eigen::Vector6d &bodyForce) override
Definition: GenericJoint.hpp:2535
void resetAccelerations() override
Definition: GenericJoint.hpp:1160
void setAcceleration(std::size_t index, double acceleration) override
Definition: GenericJoint.hpp:1001
void addChildArtInertiaToKinematic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition: GenericJoint.hpp:1815
double getConstraintImpulse(std::size_t index) const override
Definition: GenericJoint.hpp:1373
size_t getIndexInSkeleton(size_t index) const override
Definition: GenericJoint.hpp:300
void resetVelocityChanges() override
Definition: GenericJoint.hpp:1352
static constexpr ActuatorType PASSIVE
Definition: Joint.hpp:67
static constexpr ActuatorType SERVO
Definition: Joint.hpp:68
static constexpr ActuatorType ACCELERATION
Definition: Joint.hpp:70
void updateArticulatedInertia() const
Tells the Skeleton to update the articulated inertia if it needs updating.
Definition: Joint.cpp:563
static constexpr ActuatorType LOCKED
Definition: Joint.hpp:72
static constexpr ActuatorType FORCE
Definition: Joint.hpp:66
static constexpr ActuatorType MIMIC
Definition: Joint.hpp:69
void setProperties(const Properties &properties)
Set the Properties of this Joint.
Definition: Joint.cpp:110
static constexpr ActuatorType VELOCITY
Definition: Joint.hpp:71
#define GenericJoint_REPORT_UNSUPPORTED_ACTUATOR(func)
Definition: GenericJoint.hpp:61
#define GenericJoint_REPORT_DIM_MISMATCH(func, arg)
Definition: GenericJoint.hpp:44
#define GenericJoint_REPORT_OUT_OF_RANGE(func, index)
Definition: GenericJoint.hpp:53
#define GenericJoint_SET_IF_DIFFERENT(mField, value)
Definition: GenericJoint.hpp:69
Matrix< double, 6, 1 > Vector6d
Definition: MathTypes.hpp:49
Matrix< double, 6, 6 > Matrix6d
Definition: MathTypes.hpp:50
std::shared_ptr< Skeleton > SkeletonPtr
Definition: SmartPointer.hpp:60
SpaceT::Matrix inverse(const typename SpaceT::Matrix &mat)
Definition: ConfigurationSpace.hpp:188
T clip(const T &val, const T &lower, const T &upper)
Definition: Helpers.hpp:147
Eigen::Matrix< double, 6, Eigen::Dynamic > Jacobian
Definition: MathTypes.hpp:108
Eigen::Vector6d AdInvT(const Eigen::Isometry3d &_T, const Eigen::Vector6d &_V)
fast version of Ad(Inv(T), V)
Definition: Geometry.cpp:714
Eigen::Vector6d dAdInvT(const Eigen::Isometry3d &_T, const Eigen::Vector6d &_F)
fast version of dAd(Inv(T), F)
Definition: Geometry.cpp:784
Eigen::Vector6d ad(const Eigen::Vector6d &_X, const Eigen::Vector6d &_Y)
adjoint mapping
Definition: Geometry.cpp:744
Inertia transformInertia(const Eigen::Isometry3d &_T, const Inertia &_I)
Definition: Geometry.cpp:1311
bool isNan(double _v)
Returns whether _v is a NaN (Not-A-Number) value.
Definition: Helpers.hpp:173
Definition: BulletCollisionDetector.cpp:63
Definition: GenericJointAspect.hpp:178
Definition: GenericJointAspect.hpp:87
EuclideanPoint mInitialPositions
Initial positions.
Definition: GenericJointAspect.hpp:101
Vector mInitialVelocities
Initial velocities.
Definition: GenericJointAspect.hpp:110
Definition: JointAspect.hpp:112