DART 6.6.2
Loading...
Searching...
No Matches
Skeleton.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2018, 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_SKELETON_HPP_
34#define DART_DYNAMICS_SKELETON_HPP_
35
36#include <mutex>
49
50namespace dart {
51namespace dynamics {
52
54class Skeleton :
55 public virtual common::VersionCounter,
56 public MetaSkeleton,
57 public SkeletonSpecializedFor<ShapeNode, EndEffector, Marker>,
59{
60public:
61 // Some of non-virtual functions of MetaSkeleton are hidden because of the
62 // functions of the same name in this class. We expose those functions as
63 // follows.
71
74
77
88
95 {
97 const Eigen::VectorXd& positions = Eigen::VectorXd(),
98 const Eigen::VectorXd& velocities = Eigen::VectorXd(),
99 const Eigen::VectorXd& accelerations = Eigen::VectorXd(),
100 const Eigen::VectorXd& forces = Eigen::VectorXd(),
101 const Eigen::VectorXd& commands = Eigen::VectorXd());
102
104 const std::vector<std::size_t>& indices,
105 const Eigen::VectorXd& positions = Eigen::VectorXd(),
106 const Eigen::VectorXd& velocities = Eigen::VectorXd(),
107 const Eigen::VectorXd& accelerations = Eigen::VectorXd(),
108 const Eigen::VectorXd& forces = Eigen::VectorXd(),
109 const Eigen::VectorXd& commands = Eigen::VectorXd());
110
113 std::vector<std::size_t> mIndices;
114
116 Eigen::VectorXd mPositions;
117
119 Eigen::VectorXd mVelocities;
120
122 Eigen::VectorXd mAccelerations;
123
125 Eigen::VectorXd mForces;
126
128 Eigen::VectorXd mCommands;
129
131 bool operator==(const Configuration& other) const;
132
134 bool operator!=(const Configuration& other) const;
135 };
136
137 //----------------------------------------------------------------------------
139 //----------------------------------------------------------------------------
140
142 static SkeletonPtr create(const std::string& _name="Skeleton");
143
146
149
151 ConstSkeletonPtr getPtr() const;
152
156
160
162 std::mutex& getMutex() const;
163
165 std::unique_ptr<common::LockableReference> getLockableReference() const
166 override;
167
168 Skeleton(const Skeleton&) = delete;
169
171 virtual ~Skeleton();
172
174 Skeleton& operator=(const Skeleton& _other) = delete;
175
177 SkeletonPtr clone() const;
178
180 SkeletonPtr clone(const std::string& cloneName) const;
181
183
184 //----------------------------------------------------------------------------
186 //----------------------------------------------------------------------------
187
189 void setConfiguration(const Configuration& configuration);
190
192 Configuration getConfiguration(int flags = CONFIG_ALL) const;
193
195 Configuration getConfiguration(const std::vector<std::size_t>& indices,
196 int flags = CONFIG_ALL) const;
197
199
200 //----------------------------------------------------------------------------
202 //----------------------------------------------------------------------------
203
205 void setState(const State& state);
206
208 State getState() const;
209
211
212 //----------------------------------------------------------------------------
214 //----------------------------------------------------------------------------
215
218
221
224
226 DART_DEPRECATED(6.0)
228
231
233 const std::string& setName(const std::string& _name) override;
234
236 const std::string& getName() const override;
237
240 DART_DEPRECATED(6.0)
242
244 DART_DEPRECATED(6.0)
246
248 void setSelfCollisionCheck(bool enable);
249
251 bool getSelfCollisionCheck() const;
252
255
258
260 bool isEnabledSelfCollisionCheck() const;
261
264 void setAdjacentBodyCheck(bool enable);
265
267 bool getAdjacentBodyCheck() const;
268
272
276
278 bool isEnabledAdjacentBodyCheck() const;
279
282 void setMobile(bool _isMobile);
283
286 bool isMobile() const;
287
290 void setTimeStep(double _timeStep);
291
293 double getTimeStep() const;
294
297 void setGravity(const Eigen::Vector3d& _gravity);
298
300 const Eigen::Vector3d& getGravity() const;
301
303
304 //----------------------------------------------------------------------------
306 //----------------------------------------------------------------------------
307
308#ifdef _WIN32
309 template <typename JointType>
310 static typename JointType::Properties createJointProperties()
311 {
312 return typename JointType::Properties();
313 }
314
315 template <typename NodeType>
316 static typename NodeType::Properties createBodyNodeProperties()
317 {
318 return typename NodeType::Properties();
319 }
320#endif
321 // TODO: Workaround for MSVC bug on template function specialization with
322 // default argument. Please see #487 for detail
323
326 template <class JointType, class NodeType = BodyNode>
327 std::pair<JointType*, NodeType*> createJointAndBodyNodePair(
328 BodyNode* _parent = nullptr,
329#ifdef _WIN32
330 const typename JointType::Properties& _jointProperties
331 = Skeleton::createJointProperties<JointType>(),
332 const typename NodeType::Properties& _bodyProperties
333 = Skeleton::createBodyNodeProperties<NodeType>());
334#else
335 const typename JointType::Properties& _jointProperties
336 = typename JointType::Properties(),
337 const typename NodeType::Properties& _bodyProperties
338 = typename NodeType::Properties());
339#endif
340 // TODO: Workaround for MSVC bug on template function specialization with
341 // default argument. Please see #487 for detail
342
343 // Documentation inherited
344 std::size_t getNumBodyNodes() const override;
345
347 std::size_t getNumRigidBodyNodes() const;
348
350 std::size_t getNumSoftBodyNodes() const;
351
353 std::size_t getNumTrees() const;
354
356 BodyNode* getRootBodyNode(std::size_t _treeIdx = 0);
357
360 const BodyNode* getRootBodyNode(std::size_t _treeIdx = 0) const;
361
363 Joint* getRootJoint(std::size_t treeIdx = 0u);
364
367 const Joint* getRootJoint(std::size_t treeIdx = 0u) const;
368
369 // Documentation inherited
370 BodyNode* getBodyNode(std::size_t _idx) override;
371
372 // Documentation inherited
373 const BodyNode* getBodyNode(std::size_t _idx) const override;
374
376 SoftBodyNode* getSoftBodyNode(std::size_t _idx);
377
379 const SoftBodyNode* getSoftBodyNode(std::size_t _idx) const;
380
381 // Documentation inherited
382 BodyNode* getBodyNode(const std::string& name) override;
383
384 // Documentation inherited
385 const BodyNode* getBodyNode(const std::string& name) const override;
386
388 SoftBodyNode* getSoftBodyNode(const std::string& _name);
389
391 const SoftBodyNode* getSoftBodyNode(const std::string& _name) const;
392
393 // Documentation inherited
394 const std::vector<BodyNode*>& getBodyNodes() override;
395
396 // Documentation inherited
397 const std::vector<const BodyNode*>& getBodyNodes() const override;
398
404 std::vector<BodyNode*> getBodyNodes(const std::string& name) override;
405
411 std::vector<const BodyNode*> getBodyNodes(
412 const std::string& name) const override;
413
414 // Documentation inherited
415 bool hasBodyNode(const BodyNode* bodyNode) const override;
416
417 // Documentation inherited
418 std::size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const override;
419
421 const std::vector<BodyNode*>& getTreeBodyNodes(std::size_t _treeIdx);
422
424 std::vector<const BodyNode*> getTreeBodyNodes(std::size_t _treeIdx) const;
425
426 // Documentation inherited
427 std::size_t getNumJoints() const override;
428
429 // Documentation inherited
430 Joint* getJoint(std::size_t _idx) override;
431
432 // Documentation inherited
433 const Joint* getJoint(std::size_t _idx) const override;
434
435 // Documentation inherited
436 Joint* getJoint(const std::string& name) override;
437
438 // Documentation inherited
439 const Joint* getJoint(const std::string& name) const override;
440
441 // Documentation inherited
442 std::vector<Joint*> getJoints() override;
443
444 // Documentation inherited
445 std::vector<const Joint*> getJoints() const override;
446
451 std::vector<Joint*> getJoints(const std::string& name) override;
452
457 std::vector<const Joint*> getJoints(const std::string& name) const override;
458
459 // Documentation inherited
460 bool hasJoint(const Joint* joint) const override;
461
462 // Documentation inherited
463 std::size_t getIndexOf(const Joint* _joint, bool _warning=true) const override;
464
465 // Documentation inherited
466 std::size_t getNumDofs() const override;
467
468 // Documentation inherited
469 DegreeOfFreedom* getDof(std::size_t _idx) override;
470
471 // Documentation inherited
472 const DegreeOfFreedom* getDof(std::size_t _idx) const override;
473
475 DegreeOfFreedom* getDof(const std::string& _name);
476
478 const DegreeOfFreedom* getDof(const std::string& _name) const;
479
480 // Documentation inherited
481 const std::vector<DegreeOfFreedom*>& getDofs() override;
482
483 // Documentation inherited
484 std::vector<const DegreeOfFreedom*> getDofs() const override;
485
486 // Documentation inherited
487 std::size_t getIndexOf(const DegreeOfFreedom* _dof,
488 bool _warning=true) const override;
489
491 const std::vector<DegreeOfFreedom*>& getTreeDofs(std::size_t _treeIdx);
492
494 const std::vector<const DegreeOfFreedom*>& getTreeDofs(std::size_t _treeIdx) const;
495
499 bool checkIndexingConsistency() const;
500
504 const std::shared_ptr<WholeBodyIK>& getIK(bool _createIfNull = false);
505
509 const std::shared_ptr<WholeBodyIK>& getOrCreateIK();
510
514 std::shared_ptr<const WholeBodyIK> getIK() const;
515
519 const std::shared_ptr<WholeBodyIK>& createIK();
520
523 void clearIK();
524
526
528
530
531
532
533 //----------------------------------------------------------------------------
534 // Integration and finite difference
535 //----------------------------------------------------------------------------
536
537 // Documentation inherited
538 void integratePositions(double _dt);
539
540 // Documentation inherited
541 void integrateVelocities(double _dt);
542
547 Eigen::VectorXd getPositionDifferences(
548 const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const;
549
553 Eigen::VectorXd getVelocityDifferences(
554 const Eigen::VectorXd& _dq2, const Eigen::VectorXd& _dq1) const;
555
556 //----------------------------------------------------------------------------
558 //----------------------------------------------------------------------------
559
564
567 const math::SupportPolygon& getSupportPolygon(std::size_t _treeIdx) const;
568
571 const std::vector<std::size_t>& getSupportIndices() const;
572
575 const std::vector<std::size_t>& getSupportIndices(std::size_t _treeIdx) const;
576
581 const std::pair<Eigen::Vector3d, Eigen::Vector3d>& getSupportAxes() const;
582
585 const std::pair<Eigen::Vector3d, Eigen::Vector3d>& getSupportAxes(
586 std::size_t _treeIdx) const;
587
590 const Eigen::Vector2d& getSupportCentroid() const;
591
595 const Eigen::Vector2d& getSupportCentroid(std::size_t _treeIdx) const;
596
602 std::size_t getSupportVersion() const;
603
606 std::size_t getSupportVersion(std::size_t _treeIdx) const;
607
609
610 //----------------------------------------------------------------------------
611 // Kinematics algorithms
612 //----------------------------------------------------------------------------
613
642 void computeForwardKinematics(bool _updateTransforms = true,
643 bool _updateVels = true,
644 bool _updateAccs = true);
645
646 //----------------------------------------------------------------------------
647 // Dynamics algorithms
648 //----------------------------------------------------------------------------
649
652
654 void computeInverseDynamics(bool _withExternalForces = false,
655 bool _withDampingForces = false,
656 bool _withSpringForces = false);
657
658 //----------------------------------------------------------------------------
659 // Impulse-based dynamics algorithms
660 //----------------------------------------------------------------------------
661
666
668 void updateBiasImpulse(BodyNode* _bodyNode);
669
673 void updateBiasImpulse(BodyNode* _bodyNode, const Eigen::Vector6d& _imp);
674
680 void updateBiasImpulse(BodyNode* _bodyNode1, const Eigen::Vector6d& _imp1,
681 BodyNode* _bodyNode2, const Eigen::Vector6d& _imp2);
682
684 void updateBiasImpulse(SoftBodyNode* _softBodyNode,
685 PointMass* _pointMass,
686 const Eigen::Vector3d& _imp);
687
691
692 // TODO(JS): Better naming
695 void setImpulseApplied(bool _val);
696
698 bool isImpulseApplied() const;
699
702
703 //----------------------------------------------------------------------------
705 //----------------------------------------------------------------------------
706
707 // Documentation inherited
708 math::Jacobian getJacobian(const JacobianNode* _node) const override;
709
710 // Documentation inherited
712 const JacobianNode* _node,
713 const Frame* _inCoordinatesOf) const override;
714
715 // Documentation inherited
717 const JacobianNode* _node,
718 const Eigen::Vector3d& _localOffset) const override;
719
720 // Documentation inherited
722 const JacobianNode* _node,
723 const Eigen::Vector3d& _localOffset,
724 const Frame* _inCoordinatesOf) const override;
725
726 // Documentation inherited
728 const JacobianNode* _node) const override;
729
730 // Documentation inherited
732 const JacobianNode* _node,
733 const Eigen::Vector3d& _localOffset) const override;
734
735 // Documentation inherited
737 const JacobianNode* _node,
738 const Frame* _inCoordinatesOf = Frame::World()) const override;
739
740 // Documentation inherited
742 const JacobianNode* _node,
743 const Eigen::Vector3d& _localOffset,
744 const Frame* _inCoordinatesOf = Frame::World()) const override;
745
746 // Documentation inherited
748 const JacobianNode* _node,
749 const Frame* _inCoordinatesOf = Frame::World()) const override;
750
751 // Documentation inherited
753 const JacobianNode* _node) const override;
754
755 // Documentation inherited
757 const JacobianNode* _node,
758 const Frame* _inCoordinatesOf) const override;
759
760 // Documentation inherited
762 const JacobianNode* _node,
763 const Eigen::Vector3d& _localOffset) const override;
764
765 // Documentation inherited
767 const JacobianNode* _node,
768 const Eigen::Vector3d& _localOffset,
769 const Frame* _inCoordinatesOf) const override;
770
771 // Documentation inherited
773 const JacobianNode* _node) const override;
774
775 // Documentation inherited
777 const JacobianNode* _node,
778 const Frame* _inCoordinatesOf) const override;
779
780 // Documentation inherited
782 const JacobianNode* _node,
783 const Eigen::Vector3d& _localOffset,
784 const Frame* _inCoordinatesOf = Frame::World()) const override;
785
786 // Documentation inherited
788 const JacobianNode* _node,
789 const Frame* _inCoordinatesOf = Frame::World()) const override;
790
791 // Documentation inherited
793 const JacobianNode* _node,
794 const Eigen::Vector3d& _localOffset,
795 const Frame* _inCoordinatesOf = Frame::World()) const override;
796
797 // Documentation inherited
799 const JacobianNode* _node,
800 const Frame* _inCoordinatesOf = Frame::World()) const override;
801
803
804 //----------------------------------------------------------------------------
806 //----------------------------------------------------------------------------
807
811 double getMass() const override;
812
814 const Eigen::MatrixXd& getMassMatrix(std::size_t _treeIdx) const;
815
816 // Documentation inherited
817 const Eigen::MatrixXd& getMassMatrix() const override;
818
820 const Eigen::MatrixXd& getAugMassMatrix(std::size_t _treeIdx) const;
821
822 // Documentation inherited
823 const Eigen::MatrixXd& getAugMassMatrix() const override;
824
826 const Eigen::MatrixXd& getInvMassMatrix(std::size_t _treeIdx) const;
827
828 // Documentation inherited
829 const Eigen::MatrixXd& getInvMassMatrix() const override;
830
832 const Eigen::MatrixXd& getInvAugMassMatrix(std::size_t _treeIdx) const;
833
834 // Documentation inherited
835 const Eigen::MatrixXd& getInvAugMassMatrix() const override;
836
838 const Eigen::VectorXd& getCoriolisForces(std::size_t _treeIdx) const;
839
840 // Documentation inherited
841 const Eigen::VectorXd& getCoriolisForces() const override;
842
844 const Eigen::VectorXd& getGravityForces(std::size_t _treeIdx) const;
845
846 // Documentation inherited
847 const Eigen::VectorXd& getGravityForces() const override;
848
850 const Eigen::VectorXd& getCoriolisAndGravityForces(std::size_t _treeIdx) const;
851
852 // Documentation inherited
853 const Eigen::VectorXd& getCoriolisAndGravityForces() const override;
854
856 const Eigen::VectorXd& getExternalForces(std::size_t _treeIdx) const;
857
858 // Documentation inherited
859 const Eigen::VectorXd& getExternalForces() const override;
860
862// const Eigen::VectorXd& getDampingForceVector();
863
865 const Eigen::VectorXd& getConstraintForces(std::size_t _treeIdx) const;
866
868 const Eigen::VectorXd& getConstraintForces() const override;
869
870 // Documentation inherited
871 void clearExternalForces() override;
872
873 // Documentation inherited
874 void clearInternalForces() override;
875
878 DART_DEPRECATED(6.2)
879 void notifyArticulatedInertiaUpdate(std::size_t _treeIdx);
880
883 void dirtyArticulatedInertia(std::size_t _treeIdx);
884
886 DART_DEPRECATED(6.2)
887 void notifySupportUpdate(std::size_t _treeIdx);
888
890 void dirtySupportPolygon(std::size_t _treeIdx);
891
892 // Documentation inherited
893 double computeKineticEnergy() const override;
894
895 // Documentation inherited
896 double computePotentialEnergy() const override;
897
898 // Documentation inherited
899 DART_DEPRECATED(6.0)
900 void clearCollidingBodies() override;
901
903
904 //----------------------------------------------------------------------------
906 //----------------------------------------------------------------------------
907
909 Eigen::Vector3d getCOM(
910 const Frame* _withRespectTo = Frame::World()) const override;
911
915 const Frame* _relativeTo = Frame::World(),
916 const Frame* _inCoordinatesOf = Frame::World()) const override;
917
920 Eigen::Vector3d getCOMLinearVelocity(
921 const Frame* _relativeTo = Frame::World(),
922 const Frame* _inCoordinatesOf = Frame::World()) const override;
923
927 const Frame* _relativeTo = Frame::World(),
928 const Frame* _inCoordinatesOf = Frame::World()) const override;
929
933 const Frame* _relativeTo = Frame::World(),
934 const Frame* _inCoordinatesOf = Frame::World()) const override;
935
938 math::Jacobian getCOMJacobian(
939 const Frame* _inCoordinatesOf = Frame::World()) const override;
940
943 math::LinearJacobian getCOMLinearJacobian(
944 const Frame* _inCoordinatesOf = Frame::World()) const override;
945
952 math::Jacobian getCOMJacobianSpatialDeriv(
953 const Frame* _inCoordinatesOf = Frame::World()) const override;
954
961 math::LinearJacobian getCOMLinearJacobianDeriv(
962 const Frame* _inCoordinatesOf = Frame::World()) const override;
963
965
966 //----------------------------------------------------------------------------
967 // Friendship
968 //----------------------------------------------------------------------------
969 friend class BodyNode;
970 friend class SoftBodyNode;
971 friend class Joint;
972 template<class> friend class GenericJoint;
973 friend class DegreeOfFreedom;
974 friend class Node;
975 friend class ShapeNode;
976 friend class EndEffector;
977
978protected:
979 struct DataCache;
980
982 Skeleton(const AspectPropertiesData& _properties);
983
985 void setPtr(const SkeletonPtr& _ptr);
986
988 void constructNewTree();
989
991 void registerBodyNode(BodyNode* _newBodyNode);
992
994 void registerJoint(Joint* _newJoint);
995
997 void registerNode(NodeMap& nodeMap, Node* _newNode, std::size_t& _index);
998
1000 void registerNode(Node* _newNode);
1001
1003 void destructOldTree(std::size_t tree);
1004
1006 void unregisterBodyNode(BodyNode* _oldBodyNode);
1007
1009 void unregisterJoint(Joint* _oldJoint);
1010
1012 void unregisterNode(NodeMap& nodeMap, Node* _oldNode, std::size_t& _index);
1013
1015 void unregisterNode(Node* _oldNode);
1016
1018 bool moveBodyNodeTree(Joint* _parentJoint, BodyNode* _bodyNode,
1019 SkeletonPtr _newSkeleton,
1020 BodyNode* _parentNode);
1021
1026 template <class JointType>
1027 JointType* moveBodyNodeTree(
1028 BodyNode* _bodyNode,
1029 const SkeletonPtr& _newSkeleton,
1030 BodyNode* _parentNode,
1031 const typename JointType::Properties& _joint);
1032
1036 Joint* _parentJoint,
1037 const BodyNode* _bodyNode,
1038 const SkeletonPtr& _newSkeleton,
1039 BodyNode* _parentNode,
1040 bool _recursive) const;
1041
1044 template <class JointType>
1045 std::pair<JointType*, BodyNode*> cloneBodyNodeTree(
1046 const BodyNode* _bodyNode,
1047 const SkeletonPtr& _newSkeleton,
1048 BodyNode* _parentNode,
1049 const typename JointType::Properties& _joint,
1050 bool _recursive) const;
1051
1053 std::vector<const BodyNode*> constructBodyNodeTree(
1054 const BodyNode* _bodyNode) const;
1055
1056 std::vector<BodyNode*> constructBodyNodeTree(BodyNode* _bodyNode);
1057
1060 std::vector<BodyNode*> extractBodyNodeTree(BodyNode* _bodyNode);
1061
1063 void receiveBodyNodeTree(const std::vector<BodyNode*>& _tree);
1064
1066 void updateTotalMass();
1067
1069 void updateCacheDimensions(DataCache& _cache);
1070
1072 void updateCacheDimensions(std::size_t _treeIdx);
1073
1075 void updateArticulatedInertia(std::size_t _tree) const;
1076
1078 void updateArticulatedInertia() const;
1079
1081 void updateMassMatrix(std::size_t _treeIdx) const;
1082
1084 void updateMassMatrix() const;
1085
1086 void updateAugMassMatrix(std::size_t _treeIdx) const;
1087
1089 void updateAugMassMatrix() const;
1090
1092 void updateInvMassMatrix(std::size_t _treeIdx) const;
1093
1095 void updateInvMassMatrix() const;
1096
1098 void updateInvAugMassMatrix(std::size_t _treeIdx) const;
1099
1101 void updateInvAugMassMatrix() const;
1102
1104 void updateCoriolisForces(std::size_t _treeIdx) const;
1105
1107 void updateCoriolisForces() const;
1108
1110 void updateGravityForces(std::size_t _treeIdx) const;
1111
1113 void updateGravityForces() const;
1114
1116 void updateCoriolisAndGravityForces(std::size_t _treeIdx) const;
1117
1119 void updateCoriolisAndGravityForces() const;
1120
1122 void updateExternalForces(std::size_t _treeIdx) const;
1123
1124 // TODO(JS): Not implemented yet
1126 void updateExternalForces() const;
1127
1129 const Eigen::VectorXd& computeConstraintForces(DataCache& cache) const;
1130
1131// /// Update damping force vector.
1132// virtual void updateDampingForceVector();
1133
1135 const std::string& addEntryToBodyNodeNameMgr(BodyNode* _newNode);
1136
1138 const std::string& addEntryToJointNameMgr(Joint* _newJoint, bool _updateDofNames=true);
1139
1142
1143protected:
1144
1146 std::weak_ptr<Skeleton> mPtr;
1147
1150
1152 dart::common::NameManager<BodyNode*> mNameMgrForBodyNodes;
1153
1155 dart::common::NameManager<Joint*> mNameMgrForJoints;
1156
1158 dart::common::NameManager<DegreeOfFreedom*> mNameMgrForDofs;
1159
1162
1165
1167 {
1169 DirtyFlags();
1170
1173
1176
1179
1182
1185
1188
1191
1194
1197
1200
1203
1206 std::size_t mSupportVersion;
1207 };
1208
1210 {
1212
1214 std::vector<BodyNode*> mBodyNodes;
1215
1217 std::vector<const BodyNode*> mConstBodyNodes;
1218
1220 std::vector<DegreeOfFreedom*> mDofs;
1221
1223 std::vector<const DegreeOfFreedom*> mConstDofs;
1224
1226 Eigen::MatrixXd mM;
1227
1229 Eigen::MatrixXd mAugM;
1230
1232 Eigen::MatrixXd mInvM;
1233
1235 Eigen::MatrixXd mInvAugM;
1236
1238 Eigen::VectorXd mCvec;
1239
1242 Eigen::VectorXd mG;
1243
1245 Eigen::VectorXd mCg;
1246
1248 Eigen::VectorXd mFext;
1249
1251 Eigen::VectorXd mFc;
1252
1255
1258 std::vector<std::size_t> mSupportIndices;
1259
1262 std::pair<Eigen::Vector3d, Eigen::Vector3d> mSupportAxes;
1263
1266
1268 Eigen::Vector2d mSupportCentroid;
1269
1270 // To get byte-aligned Eigen vectors
1271 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1272 };
1273
1275
1277
1278 using SpecializedTreeNodes = std::map<std::type_index, std::vector<NodeMap::iterator>*>;
1279
1281
1284
1285 // TODO(JS): Better naming
1288
1289 mutable std::mutex mMutex;
1290
1291public:
1292 //--------------------------------------------------------------------------
1293 // Union finding
1294 //--------------------------------------------------------------------------
1297 {
1299 mUnionSize = 1;
1300 }
1301
1303 std::weak_ptr<Skeleton> mUnionRootSkeleton;
1304
1306 std::size_t mUnionSize;
1307
1309 std::size_t mUnionIndex;
1310};
1311
1312} // namespace dynamics
1313} // namespace dart
1314
1316
1317#endif // DART_DYNAMICS_SKELETON_HPP_
#define DART_BAKE_SPECIALIZED_NODE_SKEL_DECLARATIONS(AspectName)
Definition BasicNodeManager.hpp:320
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
BodyPropPtr properties
Definition SdfParser.cpp:80
std::string * name
Definition SkelParser.cpp:1642
detail::CompositeState State
Definition Composite.hpp:55
detail::CompositeProperties Properties
Definition Composite.hpp:56
This is an alternative to EmbedProperties which allows your class to also inherit other Composite obj...
Definition EmbeddedAspect.hpp:248
The MakeCloneable class is used to easily create an Cloneable (such as Node::State) which simply take...
Definition Cloneable.hpp:85
VersionCounter is an interface for objects that count their versions.
Definition VersionCounter.hpp:43
Definition CompositeData.hpp:104
BodyNode class represents a single node of the skeleton.
Definition BodyNode.hpp:78
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition DegreeOfFreedom.hpp:53
Definition EndEffector.hpp:84
static Frame * World()
Definition Frame.cpp:72
Definition GenericJoint.hpp:49
class Joint
Definition Joint.hpp:59
MetaSkeleton is a pure abstract base class that provides a common interface for obtaining data (such ...
Definition MetaSkeleton.hpp:62
virtual math::LinearJacobian getLinearJacobianDeriv(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const =0
of a BodyNode.
virtual math::LinearJacobian getLinearJacobian(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const =0
Get the linear Jacobian targeting the origin of a BodyNode.
virtual math::AngularJacobian getAngularJacobianDeriv(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const =0
Get the angular Jacobian time derivative of a BodyNode.
virtual math::Jacobian getJacobianClassicDeriv(const JacobianNode *_node) const =0
Get the spatial Jacobian (classical) time derivative targeting the origin of a BodyNode.
virtual math::Jacobian getJacobian(const JacobianNode *_node) const =0
Get the spatial Jacobian targeting the origin of a BodyNode.
virtual math::AngularJacobian getAngularJacobian(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const =0
Get the angular Jacobian of a BodyNode.
virtual math::Jacobian getJacobianSpatialDeriv(const JacobianNode *_node) const =0
Get the spatial Jacobian time derivative targeting the origin of a BodyNode.
The Node class is a base class for BodyNode and any object that attaches to a BodyNode.
Definition Node.hpp:84
Definition ShapeNode.hpp:49
Declaration of the variadic template.
Definition SpecializedNodeManager.hpp:120
class Skeleton
Definition Skeleton.hpp:59
Skeleton(const Skeleton &)=delete
void computeForwardDynamics()
Compute forward dynamics.
Definition Skeleton.cpp:3556
const std::vector< BodyNode * > & getBodyNodes() override
Get all the BodyNodes that are held by this MetaSkeleton.
Definition Skeleton.cpp:888
void updateInvAugMassMatrix() const
Update inverse of augmented mass matrix of the skeleton.
Definition Skeleton.cpp:3055
SoftBodyNode * getSoftBodyNode(std::size_t _idx)
Get SoftBodyNode whose index is _idx.
Definition Skeleton.cpp:839
State getState() const
Get the State of this Skeleton [alias for getCompositeState()].
Definition Skeleton.cpp:532
dart::common::NameManager< BodyNode * > mNameMgrForBodyNodes
NameManager for tracking BodyNodes.
Definition Skeleton.hpp:1152
const Eigen::MatrixXd & getMassMatrix() const override
Get the Mass Matrix of the MetaSkeleton.
Definition Skeleton.cpp:1882
SpecializedTreeNodes mSpecializedTreeNodes
Definition Skeleton.hpp:1280
dart::common::NameManager< SoftBodyNode * > mNameMgrForSoftBodyNodes
NameManager for tracking SoftBodyNodes.
Definition Skeleton.hpp:1161
void registerJoint(Joint *_newJoint)
Register a Joint with the Skeleton. Internal use only.
Definition Skeleton.cpp:2176
ConfigFlags
Definition Skeleton.hpp:79
@ CONFIG_FORCES
Definition Skeleton.hpp:84
@ CONFIG_VELOCITIES
Definition Skeleton.hpp:82
@ CONFIG_COMMANDS
Definition Skeleton.hpp:85
@ CONFIG_NOTHING
Definition Skeleton.hpp:80
@ CONFIG_ALL
Definition Skeleton.hpp:86
@ CONFIG_POSITIONS
Definition Skeleton.hpp:81
@ CONFIG_ACCELERATIONS
Definition Skeleton.hpp:83
void updateCoriolisAndGravityForces() const
Update combined vector of the skeleton.
Definition Skeleton.cpp:3226
double getMass() const override
Get total mass of the skeleton.
Definition Skeleton.cpp:1868
DegreeOfFreedom * getDof(std::size_t _idx) override
Get degree of freedom (aka generalized coordinate) whose index is _idx.
Definition Skeleton.cpp:1102
std::pair< JointType *, NodeType * > createJointAndBodyNodePair(BodyNode *_parent=nullptr, const typename JointType::Properties &_jointProperties=typename JointType::Properties(), const typename NodeType::Properties &_bodyProperties=typename NodeType::Properties())
Create a Joint and child BodyNode pair of the given types.
Definition Skeleton.hpp:77
void disableSelfCollisionCheck()
Disable self-collision check.
Definition Skeleton.cpp:670
bool isEnabledAdjacentBodyCheck() const
Return true if self-collision check is enabled including adjacent bodies.
Definition Skeleton.cpp:706
void setProperties(const Properties &properties)
Set all properties of this Skeleton.
Definition Skeleton.cpp:538
std::shared_ptr< const WholeBodyIK > getIK() const
Get a pointer to a WholeBodyIK module for this Skeleton.
Definition Skeleton.cpp:1425
void dirtyArticulatedInertia(std::size_t _treeIdx)
Notify that the articulated inertia and everything that depends on it needs to be updated.
Definition Skeleton.cpp:3615
std::size_t getIndexOf(const BodyNode *_bn, bool _warning=true) const override
Get the index of a specific BodyNode within this ReferentialSkeleton.
Definition Skeleton.cpp:963
bool isMobile() const
Get whether this skeleton will be updated by forward dynamics.
Definition Skeleton.cpp:718
void updateCoriolisForces() const
Update Coriolis force vector of the skeleton.
Definition Skeleton.cpp:3118
void clearExternalForces() override
Clear the external forces of the BodyNodes in this MetaSkeleton.
Definition Skeleton.cpp:3595
void setImpulseApplied(bool _val)
Set whether this skeleton is constrained.
Definition Skeleton.cpp:3808
SkeletonPtr getSkeleton()
Same as getPtr(), but this allows Skeleton to have a similar interface as BodyNode and Joint for temp...
Definition Skeleton.cpp:367
bool getSelfCollisionCheck() const
Return whether self-collision check is enabled.
Definition Skeleton.cpp:658
void updateArticulatedInertia() const
Update the articulated inertias of the skeleton.
Definition Skeleton.cpp:2693
void updateAugMassMatrix() const
Update augmented mass matrix of the skeleton.
Definition Skeleton.cpp:2862
void notifyArticulatedInertiaUpdate(std::size_t _treeIdx)
Notify that the articulated inertia and everything that depends on it needs to be updated.
Definition Skeleton.cpp:3609
std::pair< Joint *, BodyNode * > cloneBodyNodeTree(Joint *_parentJoint, const BodyNode *_bodyNode, const SkeletonPtr &_newSkeleton, BodyNode *_parentNode, bool _recursive) const
Copy a subtree of BodyNodes onto another Skeleton while leaving the originals intact.
Definition Skeleton.cpp:2551
std::weak_ptr< Skeleton > mPtr
The resource-managing pointer to this Skeleton.
Definition Skeleton.hpp:1146
friend class Joint
Definition Skeleton.hpp:971
void constructNewTree()
Construct a new tree in the Skeleton.
Definition Skeleton.cpp:2053
math::AngularJacobian getAngularJacobianDeriv(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const override
Get the angular Jacobian time derivative of a BodyNode.
Definition Skeleton.cpp:1861
std::size_t getNumBodyNodes() const override
Get number of body nodes.
Definition Skeleton.cpp:755
std::size_t getNumJoints() const override
Get number of Joints.
Definition Skeleton.cpp:993
void setMobile(bool _isMobile)
Set whether this skeleton will be updated by forward dynamics.
Definition Skeleton.cpp:712
void unregisterJoint(Joint *_oldJoint)
Remove a Joint from the Skeleton. Internal use only.
Definition Skeleton.cpp:2340
void unregisterBodyNode(BodyNode *_oldBodyNode)
Remove a BodyNode from the Skeleton. Internal use only.
Definition Skeleton.cpp:2275
void registerNode(NodeMap &nodeMap, Node *_newNode, std::size_t &_index)
Register a Node with the Skeleton. Internal use only.
Definition Skeleton.cpp:2203
math::LinearJacobian getCOMLinearJacobianDeriv(const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM Linear Jacobian time derivative in terms of any Frame (default is World Frame)...
Definition Skeleton.cpp:4030
const Eigen::Vector2d & getSupportCentroid() const
Get the centroid of the support polygon for this Skeleton.
Definition Skeleton.cpp:3490
bool hasBodyNode(const BodyNode *bodyNode) const override
Returns whether this Skeleton contains bodyNode.
Definition Skeleton.cpp:924
double mTotalMass
Total mass.
Definition Skeleton.hpp:1283
bool getAdjacentBodyCheck() const
Return whether adjacent body check is enabled.
Definition Skeleton.cpp:688
void computeInverseDynamics(bool _withExternalForces=false, bool _withDampingForces=false, bool _withSpringForces=false)
Compute inverse dynamics.
Definition Skeleton.cpp:3575
void updateMassMatrix() const
Update mass matrix of the skeleton.
Definition Skeleton.cpp:2767
static SkeletonPtr create(const std::string &_name="Skeleton")
Create a new Skeleton inside of a shared_ptr.
Definition Skeleton.cpp:341
const Eigen::MatrixXd & getAugMassMatrix() const override
Get augmented mass matrix of the skeleton.
Definition Skeleton.cpp:1899
void setSelfCollisionCheck(bool enable)
Set whether to check self-collision.
Definition Skeleton.cpp:652
double computeKineticEnergy() const override
Get the kinetic energy of this MetaSkeleton.
Definition Skeleton.cpp:3846
void updateInvMassMatrix() const
Update inverse of mass matrix of the skeleton.
Definition Skeleton.cpp:2958
void setTimeStep(double _timeStep)
Set time step.
Definition Skeleton.cpp:724
BodyNode * getBodyNode(std::size_t _idx) override
Get BodyNode whose index is _idx.
Definition Skeleton.cpp:825
math::Jacobian getWorldJacobian(const JacobianNode *_node) const override
Get the spatial Jacobian targeting the origin of a BodyNode.
Definition Skeleton.cpp:1635
void clearCollidingBodies() override
Clear collision flags of the BodyNodes in this MetaSkeleton.
Definition Skeleton.cpp:3872
void enableSelfCollision(bool enableAdjacentBodyCheck=false)
Deprecated.
Definition Skeleton.cpp:638
bool hasJoint(const Joint *joint) const override
Returns whether this Skeleton contains join.
Definition Skeleton.cpp:1077
const std::string & getName() const override
Get name.
Definition Skeleton.cpp:601
void setGravity(const Eigen::Vector3d &_gravity)
Set 3-dim gravitational acceleration.
Definition Skeleton.cpp:740
void updateExternalForces() const
update external force vector to generalized forces.
Definition Skeleton.cpp:3308
const Eigen::Vector3d & getGravity() const
Get 3-dim gravitational acceleration.
Definition Skeleton.cpp:749
const Eigen::VectorXd & getConstraintForces() const override
Get constraint force vector.
Definition Skeleton.cpp:2022
Eigen::VectorXd getVelocityDifferences(const Eigen::VectorXd &_dq2, const Eigen::VectorXd &_dq1) const
Return the difference of two generalized velocities or accelerations which are measured in the tangen...
Definition Skeleton.cpp:1511
std::size_t getNumSoftBodyNodes() const
Get number of soft body nodes.
Definition Skeleton.cpp:767
math::Jacobian getCOMJacobianSpatialDeriv(const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM Jacobian spatial time derivative in terms of any Frame (default is World Frame...
Definition Skeleton.cpp:4021
void setPtr(const SkeletonPtr &_ptr)
Setup this Skeleton with its shared_ptr.
Definition Skeleton.cpp:2046
const std::string & setName(const std::string &_name) override
Set name.
Definition Skeleton.cpp:573
math::LinearJacobian getLinearJacobianDeriv(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const override
of a BodyNode.
Definition Skeleton.cpp:1824
std::mutex mMutex
Definition Skeleton.hpp:1289
Configuration getConfiguration(int flags=CONFIG_ALL) const
Get the configuration of this Skeleton.
Definition Skeleton.cpp:490
Eigen::Vector3d getCOMLinearVelocity(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM linear velocity in terms of any Frame (default is World Frame)
Definition Skeleton.cpp:3941
std::vector< BodyNode * > extractBodyNodeTree(BodyNode *_bodyNode)
Create a vector representation of a subtree of BodyNodes and remove that subtree from this Skeleton w...
Definition Skeleton.cpp:2624
std::vector< SoftBodyNode * > mSoftBodyNodes
List of Soft body node list in the skeleton.
Definition Skeleton.hpp:1149
math::LinearJacobian getLinearJacobian(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const override
Get the linear Jacobian targeting the origin of a BodyNode.
Definition Skeleton.cpp:1668
friend class EndEffector
Definition Skeleton.hpp:976
virtual ~Skeleton()
Destructor.
Definition Skeleton.cpp:392
friend class DegreeOfFreedom
Definition Skeleton.hpp:973
math::AngularJacobian getAngularJacobian(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const override
Get the angular Jacobian of a BodyNode.
Definition Skeleton.cpp:1705
void integrateVelocities(double _dt)
Definition Skeleton.cpp:1466
math::Jacobian getJacobianSpatialDeriv(const JacobianNode *_node) const override
Get the spatial Jacobian time derivative targeting the origin of a BodyNode.
Definition Skeleton.cpp:1730
void unregisterNode(NodeMap &nodeMap, Node *_oldNode, std::size_t &_index)
Remove a Node from the Skeleton. Internal use only.
Definition Skeleton.cpp:2387
const std::vector< DegreeOfFreedom * > & getTreeDofs(std::size_t _treeIdx)
Get the DegreesOfFreedom belonging to a tree in this Skeleton.
Definition Skeleton.cpp:1149
SkeletonPtr getPtr()
Get the shared_ptr that manages this Skeleton.
Definition Skeleton.cpp:355
void computeForwardKinematics(bool _updateTransforms=true, bool _updateVels=true, bool _updateAccs=true)
Compute forward kinematics.
Definition Skeleton.cpp:3522
Properties getProperties() const
Get all properties of this Skeleton.
Definition Skeleton.cpp:544
const std::shared_ptr< WholeBodyIK > & getOrCreateIK()
Get a pointer to a WholeBodyIK module for this Skeleton.
Definition Skeleton.cpp:1419
const Eigen::VectorXd & getCoriolisForces() const override
Get Coriolis force vector of the MetaSkeleton's BodyNodes.
Definition Skeleton.cpp:1953
void updateBiasImpulse(BodyNode *_bodyNode)
Update bias impulses.
Definition Skeleton.cpp:3647
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this Skeleton.
Definition Skeleton.cpp:556
void disableSelfCollision()
Deprecated. Please use disableSelfCollisionCheck() instead.
Definition Skeleton.cpp:645
const Eigen::MatrixXd & getInvAugMassMatrix() const override
Get inverse of augmented Mass Matrix of the MetaSkeleton.
Definition Skeleton.cpp:1935
void resetUnion()
Definition Skeleton.hpp:1296
void enableSelfCollisionCheck()
Enable self-collision check.
Definition Skeleton.cpp:664
BodyNode * getRootBodyNode(std::size_t _treeIdx=0)
Get the root BodyNode of the tree whose index in this Skeleton is _treeIdx.
Definition Skeleton.cpp:779
friend class ShapeNode
Definition Skeleton.hpp:975
Eigen::Vector6d getCOMSpatialAcceleration(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM spatial acceleration in terms of any Frame (default is World Frame)
Definition Skeleton.cpp:3949
std::size_t getNumRigidBodyNodes() const
Get number of rigid body nodes.
Definition Skeleton.cpp:761
bool mIsImpulseApplied
Flag for status of impulse testing.
Definition Skeleton.hpp:1287
void setAdjacentBodyCheck(bool enable)
Set whether to check adjacent bodies.
Definition Skeleton.cpp:682
void dirtySupportPolygon(std::size_t _treeIdx)
Notify that the support polygon of a tree needs to be updated.
Definition Skeleton.cpp:3634
std::shared_ptr< WholeBodyIK > mWholeBodyIK
WholeBodyIK module for this Skeleton.
Definition Skeleton.hpp:1164
Eigen::Vector3d getCOM(const Frame *_withRespectTo=Frame::World()) const override
Get the Skeleton's COM with respect to any Frame (default is World Frame)
Definition Skeleton.cpp:3893
void updateGravityForces() const
Update gravity force vector of the skeleton.
Definition Skeleton.cpp:3169
std::unique_ptr< common::LockableReference > getLockableReference() const override
Get the mutex that protects the state of this Skeleton.
Definition Skeleton.cpp:385
const math::SupportPolygon & getSupportPolygon() const
Get the support polygon of this Skeleton, which is computed based on the gravitational projection of ...
Definition Skeleton.cpp:3422
friend class SoftBodyNode
Definition Skeleton.hpp:970
void computeImpulseForwardDynamics()
Compute impulse-based forward dynamics.
Definition Skeleton.cpp:3820
void updateVelocityChange()
Update velocity changes in body nodes and joints due to applied impulse.
Definition Skeleton.cpp:3801
Eigen::Vector6d getCOMSpatialVelocity(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM spatial velocity in terms of any Frame (default is World Frame)
Definition Skeleton.cpp:3933
double getTimeStep() const
Get time step.
Definition Skeleton.cpp:734
Joint * getJoint(std::size_t _idx) override
Get Joint whose index is _idx.
Definition Skeleton.cpp:1000
std::map< std::type_index, std::vector< NodeMap::iterator > * > SpecializedTreeNodes
Definition Skeleton.hpp:1278
void clearConstraintImpulses()
Clear constraint impulses and cache data used for impulse-based forward dynamics algorithm,...
Definition Skeleton.cpp:3640
bool isEnabledSelfCollisionCheck() const
Return true if self-collision check is enabled.
Definition Skeleton.cpp:676
math::LinearJacobian getCOMLinearJacobian(const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM Linear Jacobian in terms of any Frame (default is World Frame)
Definition Skeleton.cpp:4012
void disableAdjacentBodyCheck()
Disable collision check for adjacent bodies.
Definition Skeleton.cpp:700
const std::pair< Eigen::Vector3d, Eigen::Vector3d > & getSupportAxes() const
Get the axes that correspond to each component in the support polygon.
Definition Skeleton.cpp:3475
const std::vector< std::size_t > & getSupportIndices() const
Get a list of the EndEffector indices that correspond to each of the points in the support polygon.
Definition Skeleton.cpp:3460
void enableAdjacentBodyCheck()
Enable collision check for adjacent bodies.
Definition Skeleton.cpp:694
void receiveBodyNodeTree(const std::vector< BodyNode * > &_tree)
Take in and register a subtree of BodyNodes.
Definition Skeleton.cpp:2641
void notifySupportUpdate(std::size_t _treeIdx)
Notify that the support polygon of a tree needs to be updated.
Definition Skeleton.cpp:3628
bool checkIndexingConsistency() const
This function is only meant for debugging purposes.
Definition Skeleton.cpp:1163
const Eigen::VectorXd & getGravityForces() const override
Get gravity force vector of the MetaSkeleton.
Definition Skeleton.cpp:1971
const Eigen::VectorXd & getExternalForces() const override
Get external force vector of the MetaSkeleton.
Definition Skeleton.cpp:2007
friend class BodyNode
Definition Skeleton.hpp:969
std::vector< Joint * > getJoints() override
Returns all the joints that are held by this MetaSkeleton.
Definition Skeleton.cpp:1029
Eigen::VectorXd getPositionDifferences(const Eigen::VectorXd &_q2, const Eigen::VectorXd &_q1) const
Return the difference of two generalized positions which are measured in the configuration space of t...
Definition Skeleton.cpp:1479
void destructOldTree(std::size_t tree)
Remove an old tree from the Skeleton.
Definition Skeleton.cpp:2252
std::vector< const BodyNode * > constructBodyNodeTree(const BodyNode *_bodyNode) const
Create a vector representation of a subtree of BodyNodes.
Definition Skeleton.cpp:2605
std::size_t getNumTrees() const
Get the number of independent trees that this Skeleton contains.
Definition Skeleton.cpp:773
std::size_t getNumDofs() const override
Return the number of degrees of freedom in this skeleton.
Definition Skeleton.cpp:1096
const std::string & addEntryToJointNameMgr(Joint *_newJoint, bool _updateDofNames=true)
Add a Joint to to the Joint NameManager.
Definition Skeleton.cpp:616
SkeletonPtr clone() const
Create an identical clone of this Skeleton.
Definition Skeleton.cpp:399
bool moveBodyNodeTree(Joint *_parentJoint, BodyNode *_bodyNode, SkeletonPtr _newSkeleton, BodyNode *_parentNode)
Move a subtree of BodyNodes from this Skeleton to another Skeleton.
Definition Skeleton.cpp:2443
void updateCacheDimensions(DataCache &_cache)
Update the dimensions for a specific cache.
Definition Skeleton.cpp:2656
Joint * getRootJoint(std::size_t treeIdx=0u)
Get the root Joint of the tree whose index in this Skeleton is treeIdx.
Definition Skeleton.cpp:808
const Eigen::MatrixXd & getInvMassMatrix() const override
Get inverse of Mass Matrix of the MetaSkeleton.
Definition Skeleton.cpp:1917
std::mutex & getMutex() const
Get the mutex that protects the state of this Skeleton.
Definition Skeleton.cpp:379
void setState(const State &state)
Set the State of this Skeleton [alias for setCompositeState(~)].
Definition Skeleton.cpp:526
const std::shared_ptr< WholeBodyIK > & createIK()
Create a new WholeBodyIK module for this Skeleton.
Definition Skeleton.cpp:1431
void integratePositions(double _dt)
Definition Skeleton.cpp:1453
dart::common::NameManager< DegreeOfFreedom * > mNameMgrForDofs
NameManager for tracking DegreesOfFreedom.
Definition Skeleton.hpp:1158
void setConfiguration(const Configuration &configuration)
Set the configuration of this Skeleton.
Definition Skeleton.cpp:480
const AspectProperties & getSkeletonProperties() const
Get the Properties of this Skeleton.
Definition Skeleton.cpp:567
void updateTotalMass()
Update the computation for total mass.
Definition Skeleton.cpp:2648
common::aligned_vector< DataCache > mTreeCache
Definition Skeleton.hpp:1274
const std::string & addEntryToBodyNodeNameMgr(BodyNode *_newNode)
Add a BodyNode to the BodyNode NameManager.
Definition Skeleton.cpp:607
std::size_t mUnionSize
Definition Skeleton.hpp:1306
std::size_t mUnionIndex
Definition Skeleton.hpp:1309
const std::vector< BodyNode * > & getTreeBodyNodes(std::size_t _treeIdx)
Get the BodyNodes belonging to a tree in this Skeleton.
Definition Skeleton.cpp:970
void registerBodyNode(BodyNode *_newBodyNode)
Register a BodyNode with the Skeleton. Internal use only.
Definition Skeleton.cpp:2074
void addEntryToSoftBodyNodeNameMgr(SoftBodyNode *_newNode)
Add a SoftBodyNode to the SoftBodyNode NameManager.
Definition Skeleton.cpp:629
void clearInternalForces() override
Clear the internal forces of the BodyNodes in this MetaSkeleton.
Definition Skeleton.cpp:3602
std::weak_ptr< Skeleton > mUnionRootSkeleton
Definition Skeleton.hpp:1303
Skeleton & operator=(const Skeleton &_other)=delete
Remove copy operator.
const Eigen::VectorXd & getCoriolisAndGravityForces() const override
Get combined vector of Coriolis force and gravity force of the MetaSkeleton.
Definition Skeleton.cpp:1989
bool isImpulseApplied() const
Get whether this skeleton is constrained.
Definition Skeleton.cpp:3814
std::size_t getSupportVersion() const
The version number of a support polygon will be incremented each time the support polygon needs to be...
Definition Skeleton.cpp:3504
double computePotentialEnergy() const override
Get the potential energy of this MetaSkeleton.
Definition Skeleton.cpp:3858
void clearIK()
Wipe away the WholeBodyIK module for this Skeleton, leaving it as a nullptr.
Definition Skeleton.cpp:1438
dart::common::NameManager< Joint * > mNameMgrForJoints
NameManager for tracking Joints.
Definition Skeleton.hpp:1155
math::Jacobian getCOMJacobian(const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM Jacobian in terms of any Frame (default is World Frame)
Definition Skeleton.cpp:4004
Eigen::Vector3d getCOMLinearAcceleration(const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const override
Get the Skeleton's COM linear acceleration in terms of any Frame (default is World Frame)
Definition Skeleton.cpp:3958
const Eigen::VectorXd & computeConstraintForces(DataCache &cache) const
Compute the constraint force vector for a tree.
Definition Skeleton.cpp:3336
math::Jacobian getJacobianClassicDeriv(const JacobianNode *_node) const override
Get the spatial Jacobian (classical) time derivative targeting the origin of a BodyNode.
Definition Skeleton.cpp:1780
const std::vector< DegreeOfFreedom * > & getDofs() override
Get the vector of DegreesOfFreedom for this MetaSkeleton.
Definition Skeleton.cpp:1128
math::Jacobian getJacobian(const JacobianNode *_node) const override
Get the spatial Jacobian targeting the origin of a BodyNode.
Definition Skeleton.cpp:1590
DataCache mSkelCache
Definition Skeleton.hpp:1276
SoftBodyNode represent a soft body that has one deformable skin.
Definition SoftBodyNode.hpp:46
The WholeBodyIK class provides an interface for simultaneously solving all the IK constraints of all ...
Definition HierarchicalIK.hpp:357
Definition MathTypes.hpp:47
Matrix< double, 6, 1 > Vector6d
Definition MathTypes.hpp:49
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
Definition Memory.hpp:66
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition SmartPointer.hpp:60
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
Eigen::Matrix< double, 6, Eigen::Dynamic > Jacobian
Definition MathTypes.hpp:108
Eigen::Matrix< double, 3, Eigen::Dynamic > AngularJacobian
Definition MathTypes.hpp:107
Eigen::Matrix< double, 3, Eigen::Dynamic > LinearJacobian
Definition MathTypes.hpp:106
std::vector< Eigen::Vector3d > SupportGeometry
Definition Geometry.hpp:496
common::aligned_vector< Eigen::Vector2d > SupportPolygon
Definition Geometry.hpp:498
Definition BulletCollisionDetector.cpp:63
Definition SharedLibraryManager.hpp:43
The Configuration struct represents the joint configuration of a Skeleton.
Definition Skeleton.hpp:95
Eigen::VectorXd mPositions
Joint positions.
Definition Skeleton.hpp:116
bool operator!=(const Configuration &other) const
Inequality comparison operator.
Definition Skeleton.cpp:335
std::vector< std::size_t > mIndices
A list of degree of freedom indices that each entry in the Eigen::VectorXd members correspond to.
Definition Skeleton.hpp:113
Eigen::VectorXd mVelocities
Joint velocities.
Definition Skeleton.hpp:119
Eigen::VectorXd mAccelerations
Joint accelerations.
Definition Skeleton.hpp:122
bool operator==(const Configuration &other) const
Equality comparison operator.
Definition Skeleton.cpp:320
Eigen::VectorXd mCommands
Joint commands.
Definition Skeleton.hpp:128
Eigen::VectorXd mForces
Joint forces.
Definition Skeleton.hpp:125
Definition Skeleton.hpp:1210
std::vector< std::size_t > mSupportIndices
A map of which EndEffectors correspond to the individual points in the support polygon.
Definition Skeleton.hpp:1258
Eigen::VectorXd mFext
External force vector for the skeleton.
Definition Skeleton.hpp:1248
std::vector< const DegreeOfFreedom * > mConstDofs
Cache for const Degrees of Freedom, for the sake of the API.
Definition Skeleton.hpp:1223
Eigen::VectorXd mCvec
Coriolis vector for the skeleton which is C(q,dq)*dq.
Definition Skeleton.hpp:1238
Eigen::MatrixXd mInvM
Inverse of mass matrix for the skeleton.
Definition Skeleton.hpp:1232
Eigen::MatrixXd mAugM
Mass matrix for the skeleton.
Definition Skeleton.hpp:1229
Eigen::MatrixXd mInvAugM
Inverse of augmented mass matrix for the skeleton.
Definition Skeleton.hpp:1235
Eigen::VectorXd mG
Gravity vector for the skeleton; computed in nonrecursive dynamics only.
Definition Skeleton.hpp:1242
math::SupportPolygon mSupportPolygon
Support polygon.
Definition Skeleton.hpp:1254
DirtyFlags mDirty
Definition Skeleton.hpp:1211
std::vector< const BodyNode * > mConstBodyNodes
Cache for const BodyNodes, for the sake of the API.
Definition Skeleton.hpp:1217
std::vector< DegreeOfFreedom * > mDofs
Degrees of Freedom belonging to this tree.
Definition Skeleton.hpp:1220
math::SupportGeometry mSupportGeometry
Support geometry – only used for temporary storage purposes.
Definition Skeleton.hpp:1265
Eigen::Vector2d mSupportCentroid
Centroid of the support polygon.
Definition Skeleton.hpp:1268
std::pair< Eigen::Vector3d, Eigen::Vector3d > mSupportAxes
A pair of vectors which map the 2D coordinates of the support polygon into 3D space.
Definition Skeleton.hpp:1262
std::vector< BodyNode * > mBodyNodes
BodyNodes belonging to this tree.
Definition Skeleton.hpp:1214
Eigen::VectorXd mFc
Constraint force vector.
Definition Skeleton.hpp:1251
Eigen::MatrixXd mM
Mass matrix cache.
Definition Skeleton.hpp:1226
Eigen::VectorXd mCg
Combined coriolis and gravity vector which is C(q, dq)*dq + g(q).
Definition Skeleton.hpp:1245
Definition Skeleton.hpp:1167
bool mCoriolisForces
Dirty flag for the Coriolis force vector.
Definition Skeleton.hpp:1190
bool mExternalForces
Dirty flag for the external force vector.
Definition Skeleton.hpp:1196
bool mArticulatedInertia
Dirty flag for articulated body inertia.
Definition Skeleton.hpp:1172
bool mInvAugMassMatrix
Dirty flag for the inverse of augmented mass matrix.
Definition Skeleton.hpp:1184
bool mMassMatrix
Dirty flag for the mass matrix.
Definition Skeleton.hpp:1175
bool mAugMassMatrix
Dirty flag for the mass matrix.
Definition Skeleton.hpp:1178
std::size_t mSupportVersion
Increments each time a new support polygon is computed to help keep track of changes in the support p...
Definition Skeleton.hpp:1206
bool mSupport
Dirty flag for the support polygon.
Definition Skeleton.hpp:1202
bool mGravityForces
Dirty flag for the gravity force vector.
Definition Skeleton.hpp:1187
bool mDampingForces
Dirty flag for the damping force vector.
Definition Skeleton.hpp:1199
bool mCoriolisAndGravityForces
Dirty flag for the combined vector of Coriolis and gravity.
Definition Skeleton.hpp:1193
bool mInvMassMatrix
Dirty flag for the inverse of mass matrix.
Definition Skeleton.hpp:1181
The Properties of this Skeleton which are independent of the components within the Skeleton,...
Definition SkeletonAspect.hpp:54