DART 6.12.2
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Skeleton.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2021, 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>
37
50
51namespace dart {
52namespace dynamics {
53
56class Skeleton : public virtual common::VersionCounter,
57 public MetaSkeleton,
58 public SkeletonSpecializedFor<ShapeNode, EndEffector, Marker>,
60{
61public:
62 // Some of non-virtual functions of MetaSkeleton are hidden because of the
63 // functions of the same name in this class. We expose those functions as
64 // follows.
72
75
78
89
96 {
98 const Eigen::VectorXd& positions = Eigen::VectorXd(),
99 const Eigen::VectorXd& velocities = Eigen::VectorXd(),
100 const Eigen::VectorXd& accelerations = Eigen::VectorXd(),
101 const Eigen::VectorXd& forces = Eigen::VectorXd(),
102 const Eigen::VectorXd& commands = Eigen::VectorXd());
103
105 const std::vector<std::size_t>& indices,
106 const Eigen::VectorXd& positions = Eigen::VectorXd(),
107 const Eigen::VectorXd& velocities = Eigen::VectorXd(),
108 const Eigen::VectorXd& accelerations = Eigen::VectorXd(),
109 const Eigen::VectorXd& forces = Eigen::VectorXd(),
110 const Eigen::VectorXd& commands = Eigen::VectorXd());
111
114 std::vector<std::size_t> mIndices;
115
117 Eigen::VectorXd mPositions;
118
120 Eigen::VectorXd mVelocities;
121
123 Eigen::VectorXd mAccelerations;
124
126 Eigen::VectorXd mForces;
127
129 Eigen::VectorXd mCommands;
130
132 bool operator==(const Configuration& other) const;
133
135 bool operator!=(const Configuration& other) const;
136 };
137
138 //----------------------------------------------------------------------------
140 //----------------------------------------------------------------------------
141
143 static SkeletonPtr create(const std::string& _name = "Skeleton");
144
147
150
152 ConstSkeletonPtr getPtr() const;
153
157
161
163 std::mutex& getMutex() const;
164
166 std::unique_ptr<common::LockableReference> getLockableReference()
167 const override;
168
169 Skeleton(const Skeleton&) = delete;
170
172 virtual ~Skeleton();
173
175 Skeleton& operator=(const Skeleton& _other) = delete;
176
179 DART_DEPRECATED(6.7)
180 SkeletonPtr clone() const;
181 // TODO: In DART 7, change this function to override MetaSkeleton::clone()
182 // that returns MetaSkeletonPtr
183
186 DART_DEPRECATED(6.7)
187 SkeletonPtr clone(const std::string& cloneName) const;
188 // TODO: In DART 7, change this function to override MetaSkeleton::clone()
189 // that returns MetaSkeletonPtr
190
193
195 SkeletonPtr cloneSkeleton(const std::string& cloneName) const;
196
197 // Documentation inherited
199 const std::string& cloneName) const override;
200
202
203 //----------------------------------------------------------------------------
205 //----------------------------------------------------------------------------
206
208 void setConfiguration(const Configuration& configuration);
209
211 Configuration getConfiguration(int flags = CONFIG_ALL) const;
212
215 const std::vector<std::size_t>& indices, int flags = CONFIG_ALL) const;
216
218
219 //----------------------------------------------------------------------------
221 //----------------------------------------------------------------------------
222
224 void setState(const State& state);
225
227 State getState() const;
228
230
231 //----------------------------------------------------------------------------
233 //----------------------------------------------------------------------------
234
237
240
243
245 DART_DEPRECATED(6.0)
247
250
252 const std::string& setName(const std::string& _name) override;
253
255 const std::string& getName() const override;
256
259 DART_DEPRECATED(6.0)
261
263 DART_DEPRECATED(6.0)
265
267 void setSelfCollisionCheck(bool enable);
268
270 bool getSelfCollisionCheck() const;
271
274
277
279 bool isEnabledSelfCollisionCheck() const;
280
283 void setAdjacentBodyCheck(bool enable);
284
286 bool getAdjacentBodyCheck() const;
287
291
295
297 bool isEnabledAdjacentBodyCheck() const;
298
301 void setMobile(bool _isMobile);
302
305 bool isMobile() const;
306
309 void setTimeStep(double _timeStep);
310
312 double getTimeStep() const;
313
316 void setGravity(const Eigen::Vector3d& _gravity);
317
319 const Eigen::Vector3d& getGravity() const;
320
322
323 //----------------------------------------------------------------------------
325 //----------------------------------------------------------------------------
326
329 template <class JointType, class NodeType = BodyNode>
330 std::pair<JointType*, NodeType*> createJointAndBodyNodePair(
331 BodyNode* _parent = nullptr,
332 const typename JointType::Properties& _jointProperties
333 = typename JointType::Properties(),
334 const typename NodeType::Properties& _bodyProperties
335 = typename NodeType::Properties());
336
337 // Documentation inherited
338 std::size_t getNumBodyNodes() const override;
339
341 std::size_t getNumRigidBodyNodes() const;
342
344 std::size_t getNumSoftBodyNodes() const;
345
347 std::size_t getNumTrees() const;
348
350 BodyNode* getRootBodyNode(std::size_t _treeIdx = 0);
351
354 const BodyNode* getRootBodyNode(std::size_t _treeIdx = 0) const;
355
357 Joint* getRootJoint(std::size_t treeIdx = 0u);
358
361 const Joint* getRootJoint(std::size_t treeIdx = 0u) const;
362
363 // Documentation inherited
364 BodyNode* getBodyNode(std::size_t _idx) override;
365
366 // Documentation inherited
367 const BodyNode* getBodyNode(std::size_t _idx) const override;
368
370 SoftBodyNode* getSoftBodyNode(std::size_t _idx);
371
373 const SoftBodyNode* getSoftBodyNode(std::size_t _idx) const;
374
375 // Documentation inherited
376 BodyNode* getBodyNode(const std::string& name) override;
377
378 // Documentation inherited
379 const BodyNode* getBodyNode(const std::string& name) const override;
380
382 SoftBodyNode* getSoftBodyNode(const std::string& _name);
383
385 const SoftBodyNode* getSoftBodyNode(const std::string& _name) const;
386
387 // Documentation inherited
388 const std::vector<BodyNode*>& getBodyNodes() override;
389
390 // Documentation inherited
391 const std::vector<const BodyNode*>& getBodyNodes() const override;
392
398 std::vector<BodyNode*> getBodyNodes(const std::string& name) override;
399
405 std::vector<const BodyNode*> getBodyNodes(
406 const std::string& name) const override;
407
408 // Documentation inherited
409 bool hasBodyNode(const BodyNode* bodyNode) const override;
410
411 // Documentation inherited
412 std::size_t getIndexOf(
413 const BodyNode* _bn, bool _warning = true) const override;
414
416 const std::vector<BodyNode*>& getTreeBodyNodes(std::size_t _treeIdx);
417
419 std::vector<const BodyNode*> getTreeBodyNodes(std::size_t _treeIdx) const;
420
421 // Documentation inherited
422 std::size_t getNumJoints() const override;
423
424 // Documentation inherited
425 Joint* getJoint(std::size_t _idx) override;
426
427 // Documentation inherited
428 const Joint* getJoint(std::size_t _idx) const override;
429
430 // Documentation inherited
431 Joint* getJoint(const std::string& name) override;
432
433 // Documentation inherited
434 const Joint* getJoint(const std::string& name) const override;
435
436 // Documentation inherited
437 std::vector<Joint*> getJoints() override;
438
439 // Documentation inherited
440 std::vector<const Joint*> getJoints() const override;
441
446 std::vector<Joint*> getJoints(const std::string& name) override;
447
452 std::vector<const Joint*> getJoints(const std::string& name) const override;
453
454 // Documentation inherited
455 bool hasJoint(const Joint* joint) const override;
456
457 // Documentation inherited
458 std::size_t getIndexOf(
459 const Joint* _joint, bool _warning = true) const override;
460
461 // Documentation inherited
462 std::size_t getNumDofs() const override;
463
464 // Documentation inherited
465 DegreeOfFreedom* getDof(std::size_t _idx) override;
466
467 // Documentation inherited
468 const DegreeOfFreedom* getDof(std::size_t _idx) const override;
469
471 DegreeOfFreedom* getDof(const std::string& _name);
472
474 const DegreeOfFreedom* getDof(const std::string& _name) const;
475
476 // Documentation inherited
477 const std::vector<DegreeOfFreedom*>& getDofs() override;
478
479 // Documentation inherited
480 std::vector<const DegreeOfFreedom*> getDofs() const override;
481
482 // Documentation inherited
483 std::size_t getIndexOf(
484 const DegreeOfFreedom* _dof, bool _warning = true) const override;
485
487 const std::vector<DegreeOfFreedom*>& getTreeDofs(std::size_t _treeIdx);
488
490 const std::vector<const DegreeOfFreedom*>& getTreeDofs(
491 std::size_t _treeIdx) const;
492
496 bool checkIndexingConsistency() const;
497
501 const std::shared_ptr<WholeBodyIK>& getIK(bool _createIfNull = false);
502
506 const std::shared_ptr<WholeBodyIK>& getOrCreateIK();
507
511 std::shared_ptr<const WholeBodyIK> getIK() const;
512
516 const std::shared_ptr<WholeBodyIK>& createIK();
517
520 void clearIK();
521
523
525
527
529
530 //----------------------------------------------------------------------------
531 // Integration and finite difference
532 //----------------------------------------------------------------------------
533
534 // Documentation inherited
535 void integratePositions(double _dt);
536
537 // Documentation inherited
538 void integrateVelocities(double _dt);
539
545 const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const;
546
551 const Eigen::VectorXd& _dq2, const Eigen::VectorXd& _dq1) const;
552
553 //----------------------------------------------------------------------------
555 //----------------------------------------------------------------------------
556
560 const math::SupportPolygon& getSupportPolygon() const;
561
564 const math::SupportPolygon& getSupportPolygon(std::size_t _treeIdx) const;
565
568 const std::vector<std::size_t>& getSupportIndices() const;
569
572 const std::vector<std::size_t>& getSupportIndices(std::size_t _treeIdx) const;
573
578 const std::pair<Eigen::Vector3d, Eigen::Vector3d>& getSupportAxes() const;
579
582 const std::pair<Eigen::Vector3d, Eigen::Vector3d>& getSupportAxes(
583 std::size_t _treeIdx) const;
584
587 const Eigen::Vector2d& getSupportCentroid() const;
588
592 const Eigen::Vector2d& getSupportCentroid(std::size_t _treeIdx) const;
593
599 std::size_t getSupportVersion() const;
600
603 std::size_t getSupportVersion(std::size_t _treeIdx) const;
604
606
607 //----------------------------------------------------------------------------
608 // Kinematics algorithms
609 //----------------------------------------------------------------------------
610
640 bool _updateTransforms = true,
641 bool _updateVels = true,
642 bool _updateAccs = true);
643
644 //----------------------------------------------------------------------------
645 // Dynamics algorithms
646 //----------------------------------------------------------------------------
647
650
678 bool _withExternalForces = false,
679 bool _withDampingForces = false,
680 bool _withSpringForces = false);
681
682 //----------------------------------------------------------------------------
683 // Impulse-based dynamics algorithms
684 //----------------------------------------------------------------------------
685
690
692 void updateBiasImpulse(BodyNode* _bodyNode);
693
697 void updateBiasImpulse(BodyNode* _bodyNode, const Eigen::Vector6d& _imp);
698
705 BodyNode* _bodyNode1,
706 const Eigen::Vector6d& _imp1,
707 BodyNode* _bodyNode2,
708 const Eigen::Vector6d& _imp2);
709
712 SoftBodyNode* _softBodyNode,
713 PointMass* _pointMass,
714 const Eigen::Vector3d& _imp);
715
719
720 // TODO(JS): Better naming
723 void setImpulseApplied(bool _val);
724
726 bool isImpulseApplied() const;
727
730
731 //----------------------------------------------------------------------------
733 //----------------------------------------------------------------------------
734
735 // Documentation inherited
736 math::Jacobian getJacobian(const JacobianNode* _node) const override;
737
738 // Documentation inherited
739 math::Jacobian getJacobian(
740 const JacobianNode* _node, const Frame* _inCoordinatesOf) const override;
741
742 // Documentation inherited
743 math::Jacobian getJacobian(
744 const JacobianNode* _node,
745 const Eigen::Vector3d& _localOffset) const override;
746
747 // Documentation inherited
748 math::Jacobian getJacobian(
749 const JacobianNode* _node,
750 const Eigen::Vector3d& _localOffset,
751 const Frame* _inCoordinatesOf) const override;
752
753 // Documentation inherited
754 math::Jacobian getWorldJacobian(const JacobianNode* _node) const override;
755
756 // Documentation inherited
757 math::Jacobian getWorldJacobian(
758 const JacobianNode* _node,
759 const Eigen::Vector3d& _localOffset) const override;
760
761 // Documentation inherited
762 math::LinearJacobian getLinearJacobian(
763 const JacobianNode* _node,
764 const Frame* _inCoordinatesOf = Frame::World()) const override;
765
766 // Documentation inherited
767 math::LinearJacobian getLinearJacobian(
768 const JacobianNode* _node,
769 const Eigen::Vector3d& _localOffset,
770 const Frame* _inCoordinatesOf = Frame::World()) const override;
771
772 // Documentation inherited
773 math::AngularJacobian getAngularJacobian(
774 const JacobianNode* _node,
775 const Frame* _inCoordinatesOf = Frame::World()) const override;
776
777 // Documentation inherited
778 math::Jacobian getJacobianSpatialDeriv(
779 const JacobianNode* _node) const override;
780
781 // Documentation inherited
782 math::Jacobian getJacobianSpatialDeriv(
783 const JacobianNode* _node, const Frame* _inCoordinatesOf) const override;
784
785 // Documentation inherited
786 math::Jacobian getJacobianSpatialDeriv(
787 const JacobianNode* _node,
788 const Eigen::Vector3d& _localOffset) const override;
789
790 // Documentation inherited
791 math::Jacobian getJacobianSpatialDeriv(
792 const JacobianNode* _node,
793 const Eigen::Vector3d& _localOffset,
794 const Frame* _inCoordinatesOf) const override;
795
796 // Documentation inherited
797 math::Jacobian getJacobianClassicDeriv(
798 const JacobianNode* _node) const override;
799
800 // Documentation inherited
801 math::Jacobian getJacobianClassicDeriv(
802 const JacobianNode* _node, const Frame* _inCoordinatesOf) const override;
803
804 // Documentation inherited
805 math::Jacobian getJacobianClassicDeriv(
806 const JacobianNode* _node,
807 const Eigen::Vector3d& _localOffset,
808 const Frame* _inCoordinatesOf = Frame::World()) const override;
809
810 // Documentation inherited
811 math::LinearJacobian getLinearJacobianDeriv(
812 const JacobianNode* _node,
813 const Frame* _inCoordinatesOf = Frame::World()) const override;
814
815 // Documentation inherited
816 math::LinearJacobian getLinearJacobianDeriv(
817 const JacobianNode* _node,
818 const Eigen::Vector3d& _localOffset,
819 const Frame* _inCoordinatesOf = Frame::World()) const override;
820
821 // Documentation inherited
822 math::AngularJacobian getAngularJacobianDeriv(
823 const JacobianNode* _node,
824 const Frame* _inCoordinatesOf = Frame::World()) const override;
825
827
828 //----------------------------------------------------------------------------
830 //----------------------------------------------------------------------------
831
835 double getMass() const override;
836
838 const Eigen::MatrixXd& getMassMatrix(std::size_t _treeIdx) const;
839
840 // Documentation inherited
841 const Eigen::MatrixXd& getMassMatrix() const override;
842
844 const Eigen::MatrixXd& getAugMassMatrix(std::size_t _treeIdx) const;
845
846 // Documentation inherited
847 const Eigen::MatrixXd& getAugMassMatrix() const override;
848
850 const Eigen::MatrixXd& getInvMassMatrix(std::size_t _treeIdx) const;
851
852 // Documentation inherited
853 const Eigen::MatrixXd& getInvMassMatrix() const override;
854
856 const Eigen::MatrixXd& getInvAugMassMatrix(std::size_t _treeIdx) const;
857
858 // Documentation inherited
859 const Eigen::MatrixXd& getInvAugMassMatrix() const override;
860
862 const Eigen::VectorXd& getCoriolisForces(std::size_t _treeIdx) const;
863
864 // Documentation inherited
865 const Eigen::VectorXd& getCoriolisForces() const override;
866
868 const Eigen::VectorXd& getGravityForces(std::size_t _treeIdx) const;
869
870 // Documentation inherited
871 const Eigen::VectorXd& getGravityForces() const override;
872
874 const Eigen::VectorXd& getCoriolisAndGravityForces(
875 std::size_t _treeIdx) const;
876
877 // Documentation inherited
878 const Eigen::VectorXd& getCoriolisAndGravityForces() const override;
879
881 const Eigen::VectorXd& getExternalForces(std::size_t _treeIdx) const;
882
883 // Documentation inherited
884 const Eigen::VectorXd& getExternalForces() const override;
885
887 // const Eigen::VectorXd& getDampingForceVector();
888
890 const Eigen::VectorXd& getConstraintForces(std::size_t _treeIdx) const;
891
893 const Eigen::VectorXd& getConstraintForces() const override;
894
895 // Documentation inherited
896 void clearExternalForces() override;
897
898 // Documentation inherited
899 void clearInternalForces() override;
900
903 DART_DEPRECATED(6.2)
904 void notifyArticulatedInertiaUpdate(std::size_t _treeIdx);
905
908 void dirtyArticulatedInertia(std::size_t _treeIdx);
909
911 DART_DEPRECATED(6.2)
912 void notifySupportUpdate(std::size_t _treeIdx);
913
915 void dirtySupportPolygon(std::size_t _treeIdx);
916
917 // Documentation inherited
918 double computeKineticEnergy() const override;
919
920 // Documentation inherited
921 double computePotentialEnergy() const override;
922
923 // Documentation inherited
924 DART_DEPRECATED(6.0)
925 void clearCollidingBodies() override;
926
928
929 //----------------------------------------------------------------------------
931 //----------------------------------------------------------------------------
932
934 Eigen::Vector3d getCOM(
935 const Frame* _withRespectTo = Frame::World()) const override;
936
940 const Frame* _relativeTo = Frame::World(),
941 const Frame* _inCoordinatesOf = Frame::World()) const override;
942
945 Eigen::Vector3d getCOMLinearVelocity(
946 const Frame* _relativeTo = Frame::World(),
947 const Frame* _inCoordinatesOf = Frame::World()) const override;
948
952 const Frame* _relativeTo = Frame::World(),
953 const Frame* _inCoordinatesOf = Frame::World()) const override;
954
958 const Frame* _relativeTo = Frame::World(),
959 const Frame* _inCoordinatesOf = Frame::World()) const override;
960
963 math::Jacobian getCOMJacobian(
964 const Frame* _inCoordinatesOf = Frame::World()) const override;
965
968 math::LinearJacobian getCOMLinearJacobian(
969 const Frame* _inCoordinatesOf = Frame::World()) const override;
970
977 math::Jacobian getCOMJacobianSpatialDeriv(
978 const Frame* _inCoordinatesOf = Frame::World()) const override;
979
986 math::LinearJacobian getCOMLinearJacobianDeriv(
987 const Frame* _inCoordinatesOf = Frame::World()) const override;
988
990
991 //----------------------------------------------------------------------------
992 // Friendship
993 //----------------------------------------------------------------------------
994 friend class BodyNode;
995 friend class SoftBodyNode;
996 friend class Joint;
997 template <class>
998 friend class GenericJoint;
999 friend class DegreeOfFreedom;
1000 friend class Node;
1001 friend class ShapeNode;
1002 friend class EndEffector;
1003
1004protected:
1005 struct DataCache;
1006
1008 Skeleton(const AspectPropertiesData& _properties);
1009
1011 void setPtr(const SkeletonPtr& _ptr);
1012
1014 void constructNewTree();
1015
1017 void registerBodyNode(BodyNode* _newBodyNode);
1018
1020 void registerJoint(Joint* _newJoint);
1021
1023 void registerNode(NodeMap& nodeMap, Node* _newNode, std::size_t& _index);
1024
1026 void registerNode(Node* _newNode);
1027
1029 void destructOldTree(std::size_t tree);
1030
1032 void unregisterBodyNode(BodyNode* _oldBodyNode);
1033
1035 void unregisterJoint(Joint* _oldJoint);
1036
1038 void unregisterNode(NodeMap& nodeMap, Node* _oldNode, std::size_t& _index);
1039
1041 void unregisterNode(Node* _oldNode);
1042
1044 bool moveBodyNodeTree(
1045 Joint* _parentJoint,
1046 BodyNode* _bodyNode,
1047 SkeletonPtr _newSkeleton,
1048 BodyNode* _parentNode);
1049
1054 template <class JointType>
1055 JointType* moveBodyNodeTree(
1056 BodyNode* _bodyNode,
1057 const SkeletonPtr& _newSkeleton,
1058 BodyNode* _parentNode,
1059 const typename JointType::Properties& _joint);
1060
1064 Joint* _parentJoint,
1065 const BodyNode* _bodyNode,
1066 const SkeletonPtr& _newSkeleton,
1067 BodyNode* _parentNode,
1068 bool _recursive) const;
1069
1072 template <class JointType>
1073 std::pair<JointType*, BodyNode*> cloneBodyNodeTree(
1074 const BodyNode* _bodyNode,
1075 const SkeletonPtr& _newSkeleton,
1076 BodyNode* _parentNode,
1077 const typename JointType::Properties& _joint,
1078 bool _recursive) const;
1079
1081 std::vector<const BodyNode*> constructBodyNodeTree(
1082 const BodyNode* _bodyNode) const;
1083
1084 std::vector<BodyNode*> constructBodyNodeTree(BodyNode* _bodyNode);
1085
1088 std::vector<BodyNode*> extractBodyNodeTree(BodyNode* _bodyNode);
1089
1091 void receiveBodyNodeTree(const std::vector<BodyNode*>& _tree);
1092
1094 void updateTotalMass();
1095
1097 void updateCacheDimensions(DataCache& _cache);
1098
1100 void updateCacheDimensions(std::size_t _treeIdx);
1101
1103 void updateArticulatedInertia(std::size_t _tree) const;
1104
1106 void updateArticulatedInertia() const;
1107
1109 void updateMassMatrix(std::size_t _treeIdx) const;
1110
1112 void updateMassMatrix() const;
1113
1114 void updateAugMassMatrix(std::size_t _treeIdx) const;
1115
1117 void updateAugMassMatrix() const;
1118
1120 void updateInvMassMatrix(std::size_t _treeIdx) const;
1121
1123 void updateInvMassMatrix() const;
1124
1126 void updateInvAugMassMatrix(std::size_t _treeIdx) const;
1127
1129 void updateInvAugMassMatrix() const;
1130
1132 void updateCoriolisForces(std::size_t _treeIdx) const;
1133
1135 void updateCoriolisForces() const;
1136
1138 void updateGravityForces(std::size_t _treeIdx) const;
1139
1141 void updateGravityForces() const;
1142
1144 void updateCoriolisAndGravityForces(std::size_t _treeIdx) const;
1145
1147 void updateCoriolisAndGravityForces() const;
1148
1150 void updateExternalForces(std::size_t _treeIdx) const;
1151
1152 // TODO(JS): Not implemented yet
1154 void updateExternalForces() const;
1155
1157 const Eigen::VectorXd& computeConstraintForces(DataCache& cache) const;
1158
1159 // /// Update damping force vector.
1160 // virtual void updateDampingForceVector();
1161
1163 const std::string& addEntryToBodyNodeNameMgr(BodyNode* _newNode);
1164
1166 const std::string& addEntryToJointNameMgr(
1167 Joint* _newJoint, bool _updateDofNames = true);
1168
1171
1173
1174protected:
1176 std::weak_ptr<Skeleton> mPtr;
1177
1180
1182 dart::common::NameManager<BodyNode*> mNameMgrForBodyNodes;
1183
1185 dart::common::NameManager<Joint*> mNameMgrForJoints;
1186
1188 dart::common::NameManager<DegreeOfFreedom*> mNameMgrForDofs;
1189
1192
1195
1197 {
1199 DirtyFlags();
1200
1203
1206
1209
1212
1215
1218
1221
1224
1227
1230
1233
1236 std::size_t mSupportVersion;
1237 };
1238
1240 {
1242
1244 std::vector<BodyNode*> mBodyNodes;
1245
1247 std::vector<const BodyNode*> mConstBodyNodes;
1248
1250 std::vector<DegreeOfFreedom*> mDofs;
1251
1253 std::vector<const DegreeOfFreedom*> mConstDofs;
1254
1256 Eigen::MatrixXd mM;
1257
1259 Eigen::MatrixXd mAugM;
1260
1262 Eigen::MatrixXd mInvM;
1263
1265 Eigen::MatrixXd mInvAugM;
1266
1268 Eigen::VectorXd mCvec;
1269
1272 Eigen::VectorXd mG;
1273
1275 Eigen::VectorXd mCg;
1276
1278 Eigen::VectorXd mFext;
1279
1281 Eigen::VectorXd mFc;
1282
1285
1288 std::vector<std::size_t> mSupportIndices;
1289
1292 std::pair<Eigen::Vector3d, Eigen::Vector3d> mSupportAxes;
1293
1296
1298 Eigen::Vector2d mSupportCentroid;
1299
1300 // To get byte-aligned Eigen vectors
1301 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1302 };
1303
1305
1307
1309 = std::map<std::type_index, std::vector<NodeMap::iterator>*>;
1310
1312
1315
1316 // TODO(JS): Better naming
1319
1320 mutable std::mutex mMutex;
1321
1322public:
1323 //--------------------------------------------------------------------------
1324 // Union finding
1325 //--------------------------------------------------------------------------
1328 {
1330 mUnionSize = 1;
1331 }
1332
1334 std::weak_ptr<Skeleton> mUnionRootSkeleton;
1335
1337 std::size_t mUnionSize;
1338
1340 std::size_t mUnionIndex;
1341};
1343
1344} // namespace dynamics
1345} // namespace dart
1346
1348
1349#endif // DART_DYNAMICS_SKELETON_HPP_
#define DART_BAKE_SPECIALIZED_NODE_SKEL_DECLARATIONS(AspectName)
Definition BasicNodeManager.hpp:349
#define DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_END
Definition ClassWithVirtualBase.hpp:44
#define DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN
Definition ClassWithVirtualBase.hpp:43
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
BodyPropPtr properties
Definition SdfParser.cpp:80
std::string * name
Definition SkelParser.cpp:1697
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:240
The MakeCloneable class is used to easily create an Cloneable (such as Node::State) which simply take...
Definition Cloneable.hpp:84
VersionCounter is an interface for objects that count their versions.
Definition VersionCounter.hpp:43
Definition CompositeData.hpp:107
BodyNode class represents a single node of the skeleton.
Definition BodyNode.hpp:79
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition DegreeOfFreedom.hpp:56
Definition EndEffector.hpp:81
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition Frame.hpp:58
Definition GenericJoint.hpp:49
The JacobianNode class serves as a common interface for BodyNodes and EndEffectors to both be used as...
Definition JacobianNode.hpp:55
class Joint
Definition Joint.hpp:61
Definition Marker.hpp:51
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.
MetaSkeletonPtr cloneMetaSkeleton() const
Creates an identical clone of this MetaSkeleton.
Definition MetaSkeleton.cpp:329
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:80
Definition PointMass.hpp:53
Definition ShapeNode.hpp:49
Declaration of the variadic template.
Definition SpecializedNodeManager.hpp:124
class Skeleton
Definition Skeleton.hpp:60
Skeleton(const Skeleton &)=delete
void computeForwardDynamics()
Compute forward dynamics.
Definition Skeleton.cpp:3728
const std::vector< BodyNode * > & getBodyNodes() override
Get all the BodyNodes that are held by this MetaSkeleton.
Definition Skeleton.cpp:984
void updateInvAugMassMatrix() const
Update inverse of augmented mass matrix of the skeleton.
Definition Skeleton.cpp:3198
SoftBodyNode * getSoftBodyNode(std::size_t _idx)
Get SoftBodyNode whose index is _idx.
Definition Skeleton.cpp:935
State getState() const
Get the State of this Skeleton [alias for getCompositeState()].
Definition Skeleton.cpp:619
dart::common::NameManager< BodyNode * > mNameMgrForBodyNodes
NameManager for tracking BodyNodes.
Definition Skeleton.hpp:1182
const Eigen::MatrixXd & getMassMatrix() const override
Get the Mass Matrix of the MetaSkeleton.
Definition Skeleton.cpp:1978
SpecializedTreeNodes mSpecializedTreeNodes
Definition Skeleton.hpp:1311
dart::common::NameManager< SoftBodyNode * > mNameMgrForSoftBodyNodes
NameManager for tracking SoftBodyNodes.
Definition Skeleton.hpp:1191
void registerJoint(Joint *_newJoint)
Register a Joint with the Skeleton. Internal use only.
Definition Skeleton.cpp:2276
ConfigFlags
Definition Skeleton.hpp:80
@ CONFIG_FORCES
Definition Skeleton.hpp:85
@ CONFIG_VELOCITIES
Definition Skeleton.hpp:83
@ CONFIG_COMMANDS
Definition Skeleton.hpp:86
@ CONFIG_NOTHING
Definition Skeleton.hpp:81
@ CONFIG_ALL
Definition Skeleton.hpp:87
@ CONFIG_POSITIONS
Definition Skeleton.hpp:82
@ CONFIG_ACCELERATIONS
Definition Skeleton.hpp:84
void updateCoriolisAndGravityForces() const
Update combined vector of the skeleton.
Definition Skeleton.cpp:3378
double getMass() const override
Get total mass of the skeleton.
Definition Skeleton.cpp:1964
DegreeOfFreedom * getDof(std::size_t _idx) override
Get degree of freedom (aka generalized coordinate) whose index is _idx.
Definition Skeleton.cpp:1207
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:766
bool isEnabledAdjacentBodyCheck() const
Return true if self-collision check is enabled including adjacent bodies.
Definition Skeleton.cpp:802
void setProperties(const Properties &properties)
Set all properties of this Skeleton.
Definition Skeleton.cpp:625
std::shared_ptr< const WholeBodyIK > getIK() const
Get a pointer to a WholeBodyIK module for this Skeleton.
Definition Skeleton.cpp:1531
void dirtyArticulatedInertia(std::size_t _treeIdx)
Notify that the articulated inertia and everything that depends on it needs to be updated.
Definition Skeleton.cpp:3789
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:1065
bool isMobile() const
Get whether this skeleton will be updated by forward dynamics.
Definition Skeleton.cpp:814
void updateCoriolisForces() const
Update Coriolis force vector of the skeleton.
Definition Skeleton.cpp:3265
void clearExternalForces() override
Clear the external forces of the BodyNodes in this MetaSkeleton.
Definition Skeleton.cpp:3769
void setImpulseApplied(bool _val)
Set whether this skeleton is constrained.
Definition Skeleton.cpp:3991
SkeletonPtr getSkeleton()
Same as getPtr(), but this allows Skeleton to have a similar interface as BodyNode and Joint for temp...
Definition Skeleton.cpp:410
bool getSelfCollisionCheck() const
Return whether self-collision check is enabled.
Definition Skeleton.cpp:754
void updateArticulatedInertia() const
Update the articulated inertias of the skeleton.
Definition Skeleton.cpp:2815
void updateAugMassMatrix() const
Update augmented mass matrix of the skeleton.
Definition Skeleton.cpp:2994
void notifyArticulatedInertiaUpdate(std::size_t _treeIdx)
Notify that the articulated inertia and everything that depends on it needs to be updated.
Definition Skeleton.cpp:3783
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:2667
std::weak_ptr< Skeleton > mPtr
The resource-managing pointer to this Skeleton.
Definition Skeleton.hpp:1176
void constructNewTree()
Construct a new tree in the Skeleton.
Definition Skeleton.cpp:2150
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:1957
std::size_t getNumBodyNodes() const override
Get number of body nodes.
Definition Skeleton.cpp:851
std::size_t getNumJoints() const override
Get number of Joints.
Definition Skeleton.cpp:1098
void setMobile(bool _isMobile)
Set whether this skeleton will be updated by forward dynamics.
Definition Skeleton.cpp:808
void unregisterJoint(Joint *_oldJoint)
Remove a Joint from the Skeleton. Internal use only.
Definition Skeleton.cpp:2453
void unregisterBodyNode(BodyNode *_oldBodyNode)
Remove a BodyNode from the Skeleton. Internal use only.
Definition Skeleton.cpp:2381
void registerNode(NodeMap &nodeMap, Node *_newNode, std::size_t &_index)
Register a Node with the Skeleton. Internal use only.
Definition Skeleton.cpp:2305
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:4221
const Eigen::Vector2d & getSupportCentroid() const
Get the centroid of the support polygon for this Skeleton.
Definition Skeleton.cpp:3660
bool hasBodyNode(const BodyNode *bodyNode) const override
Returns whether this Skeleton contains bodyNode.
Definition Skeleton.cpp:1020
double mTotalMass
Total mass.
Definition Skeleton.hpp:1314
bool getAdjacentBodyCheck() const
Return whether adjacent body check is enabled.
Definition Skeleton.cpp:784
void computeInverseDynamics(bool _withExternalForces=false, bool _withDampingForces=false, bool _withSpringForces=false)
Computes inverse dynamics.
Definition Skeleton.cpp:3749
void updateMassMatrix() const
Update mass matrix of the skeleton.
Definition Skeleton.cpp:2893
static SkeletonPtr create(const std::string &_name="Skeleton")
Create a new Skeleton inside of a shared_ptr.
Definition Skeleton.cpp:384
const Eigen::MatrixXd & getAugMassMatrix() const override
Get augmented mass matrix of the skeleton.
Definition Skeleton.cpp:1995
void setSelfCollisionCheck(bool enable)
Set whether to check self-collision.
Definition Skeleton.cpp:748
double computeKineticEnergy() const override
Get the kinetic energy of this MetaSkeleton.
Definition Skeleton.cpp:4030
void updateInvMassMatrix() const
Update inverse of mass matrix of the skeleton.
Definition Skeleton.cpp:3095
void setTimeStep(double _timeStep)
Set time step.
Definition Skeleton.cpp:820
BodyNode * getBodyNode(std::size_t _idx) override
Get BodyNode whose index is _idx.
Definition Skeleton.cpp:921
math::Jacobian getWorldJacobian(const JacobianNode *_node) const override
Get the spatial Jacobian targeting the origin of a BodyNode.
Definition Skeleton.cpp:1744
void clearCollidingBodies() override
Clear collision flags of the BodyNodes in this MetaSkeleton.
Definition Skeleton.cpp:4056
void enableSelfCollision(bool enableAdjacentBodyCheck=false)
Deprecated.
Definition Skeleton.cpp:734
bool hasJoint(const Joint *joint) const override
Returns whether this Skeleton contains join.
Definition Skeleton.cpp:1182
const std::string & getName() const override
Get name.
Definition Skeleton.cpp:677
void setGravity(const Eigen::Vector3d &_gravity)
Set 3-dim gravitational acceleration.
Definition Skeleton.cpp:836
void updateExternalForces() const
update external force vector to generalized forces.
Definition Skeleton.cpp:3463
const Eigen::Vector3d & getGravity() const
Get 3-dim gravitational acceleration.
Definition Skeleton.cpp:845
const Eigen::VectorXd & getConstraintForces() const override
Get constraint force vector.
Definition Skeleton.cpp:2119
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:1617
std::size_t getNumSoftBodyNodes() const
Get number of soft body nodes.
Definition Skeleton.cpp:863
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:4211
void setPtr(const SkeletonPtr &_ptr)
Setup this Skeleton with its shared_ptr.
Definition Skeleton.cpp:2143
const std::string & setName(const std::string &_name) override
Set name.
Definition Skeleton.cpp:660
math::LinearJacobian getLinearJacobianDeriv(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const override
of a BodyNode.
Definition Skeleton.cpp:1921
std::mutex mMutex
Definition Skeleton.hpp:1320
Configuration getConfiguration(int flags=CONFIG_ALL) const
Get the configuration of this Skeleton.
Definition Skeleton.cpp:577
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:4127
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:2744
std::vector< SoftBodyNode * > mSoftBodyNodes
List of Soft body node list in the skeleton.
Definition Skeleton.hpp:1179
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:1774
virtual ~Skeleton()
Destructor.
Definition Skeleton.cpp:436
math::AngularJacobian getAngularJacobian(const JacobianNode *_node, const Frame *_inCoordinatesOf=Frame::World()) const override
Get the angular Jacobian of a BodyNode.
Definition Skeleton.cpp:1807
void integrateVelocities(double _dt)
Definition Skeleton.cpp:1572
math::Jacobian getJacobianSpatialDeriv(const JacobianNode *_node) const override
Get the spatial Jacobian time derivative targeting the origin of a BodyNode.
Definition Skeleton.cpp:1831
SkeletonPtr cloneSkeleton() const
Creates and returns a clone of this Skeleton.
Definition Skeleton.cpp:455
void unregisterNode(NodeMap &nodeMap, Node *_oldNode, std::size_t &_index)
Remove a Node from the Skeleton. Internal use only.
Definition Skeleton.cpp:2500
const std::vector< DegreeOfFreedom * > & getTreeDofs(std::size_t _treeIdx)
Get the DegreesOfFreedom belonging to a tree in this Skeleton.
Definition Skeleton.cpp:1256
SkeletonPtr getPtr()
Get the shared_ptr that manages this Skeleton.
Definition Skeleton.cpp:398
void computeForwardKinematics(bool _updateTransforms=true, bool _updateVels=true, bool _updateAccs=true)
Compute forward kinematics.
Definition Skeleton.cpp:3692
Properties getProperties() const
Get all properties of this Skeleton.
Definition Skeleton.cpp:631
const std::shared_ptr< WholeBodyIK > & getOrCreateIK()
Get a pointer to a WholeBodyIK module for this Skeleton.
Definition Skeleton.cpp:1525
const Eigen::VectorXd & getCoriolisForces() const override
Get Coriolis force vector of the MetaSkeleton's BodyNodes.
Definition Skeleton.cpp:2049
void updateBiasImpulse(BodyNode *_bodyNode)
Update bias impulses.
Definition Skeleton.cpp:3821
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this Skeleton.
Definition Skeleton.cpp:643
void disableSelfCollision()
Deprecated. Please use disableSelfCollisionCheck() instead.
Definition Skeleton.cpp:741
const Eigen::MatrixXd & getInvAugMassMatrix() const override
Get inverse of augmented Mass Matrix of the MetaSkeleton.
Definition Skeleton.cpp:2031
void resetUnion()
Definition Skeleton.hpp:1327
void enableSelfCollisionCheck()
Enable self-collision check.
Definition Skeleton.cpp:760
BodyNode * getRootBodyNode(std::size_t _treeIdx=0)
Get the root BodyNode of the tree whose index in this Skeleton is _treeIdx.
Definition Skeleton.cpp:875
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:4136
std::size_t getNumRigidBodyNodes() const
Get number of rigid body nodes.
Definition Skeleton.cpp:857
bool mIsImpulseApplied
Flag for status of impulse testing.
Definition Skeleton.hpp:1318
void setAdjacentBodyCheck(bool enable)
Set whether to check adjacent bodies.
Definition Skeleton.cpp:778
void dirtySupportPolygon(std::size_t _treeIdx)
Notify that the support polygon of a tree needs to be updated.
Definition Skeleton.cpp:3808
std::shared_ptr< WholeBodyIK > mWholeBodyIK
WholeBodyIK module for this Skeleton.
Definition Skeleton.hpp:1194
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:4077
void updateGravityForces() const
Update gravity force vector of the skeleton.
Definition Skeleton.cpp:3318
std::unique_ptr< common::LockableReference > getLockableReference() const override
Get the mutex that protects the state of this Skeleton.
Definition Skeleton.cpp:428
const math::SupportPolygon & getSupportPolygon() const
Get the support polygon of this Skeleton, which is computed based on the gravitational projection of ...
Definition Skeleton.cpp:3582
void updateNameManagerNames()
Definition Skeleton.cpp:714
void computeImpulseForwardDynamics()
Compute impulse-based forward dynamics.
Definition Skeleton.cpp:4003
void updateVelocityChange()
Update velocity changes in body nodes and joints due to applied impulse.
Definition Skeleton.cpp:3984
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:4118
double getTimeStep() const
Get time step.
Definition Skeleton.cpp:830
Joint * getJoint(std::size_t _idx) override
Get Joint whose index is _idx.
Definition Skeleton.cpp:1105
std::map< std::type_index, std::vector< NodeMap::iterator > * > SpecializedTreeNodes
Definition Skeleton.hpp:1309
void clearConstraintImpulses()
Clear constraint impulses and cache data used for impulse-based forward dynamics algorithm,...
Definition Skeleton.cpp:3814
bool isEnabledSelfCollisionCheck() const
Return true if self-collision check is enabled.
Definition Skeleton.cpp:772
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:4201
void disableAdjacentBodyCheck()
Disable collision check for adjacent bodies.
Definition Skeleton.cpp:796
const std::pair< Eigen::Vector3d, Eigen::Vector3d > & getSupportAxes() const
Get the axes that correspond to each component in the support polygon.
Definition Skeleton.cpp:3644
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:3629
void enableAdjacentBodyCheck()
Enable collision check for adjacent bodies.
Definition Skeleton.cpp:790
void receiveBodyNodeTree(const std::vector< BodyNode * > &_tree)
Take in and register a subtree of BodyNodes.
Definition Skeleton.cpp:2761
void notifySupportUpdate(std::size_t _treeIdx)
Notify that the support polygon of a tree needs to be updated.
Definition Skeleton.cpp:3802
bool checkIndexingConsistency() const
This function is only meant for debugging purposes.
Definition Skeleton.cpp:1270
const Eigen::VectorXd & getGravityForces() const override
Get gravity force vector of the MetaSkeleton.
Definition Skeleton.cpp:2067
const Eigen::VectorXd & getExternalForces() const override
Get external force vector of the MetaSkeleton.
Definition Skeleton.cpp:2104
std::vector< Joint * > getJoints() override
Returns all the joints that are held by this MetaSkeleton.
Definition Skeleton.cpp:1134
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:1585
void destructOldTree(std::size_t tree)
Remove an old tree from the Skeleton.
Definition Skeleton.cpp:2358
std::vector< const BodyNode * > constructBodyNodeTree(const BodyNode *_bodyNode) const
Create a vector representation of a subtree of BodyNodes.
Definition Skeleton.cpp:2725
std::size_t getNumTrees() const
Get the number of independent trees that this Skeleton contains.
Definition Skeleton.cpp:869
std::size_t getNumDofs() const override
Return the number of degrees of freedom in this skeleton.
Definition Skeleton.cpp:1201
const std::string & addEntryToJointNameMgr(Joint *_newJoint, bool _updateDofNames=true)
Add a Joint to to the Joint NameManager.
Definition Skeleton.cpp:692
SkeletonPtr clone() const
Create an identical clone of this Skeleton.
Definition Skeleton.cpp:443
bool moveBodyNodeTree(Joint *_parentJoint, BodyNode *_bodyNode, SkeletonPtr _newSkeleton, BodyNode *_parentNode)
Move a subtree of BodyNodes from this Skeleton to another Skeleton.
Definition Skeleton.cpp:2557
void updateCacheDimensions(DataCache &_cache)
Update the dimensions for a specific cache.
Definition Skeleton.cpp:2776
Joint * getRootJoint(std::size_t treeIdx=0u)
Get the root Joint of the tree whose index in this Skeleton is treeIdx.
Definition Skeleton.cpp:904
const Eigen::MatrixXd & getInvMassMatrix() const override
Get inverse of Mass Matrix of the MetaSkeleton.
Definition Skeleton.cpp:2013
std::mutex & getMutex() const
Get the mutex that protects the state of this Skeleton.
Definition Skeleton.cpp:422
void setState(const State &state)
Set the State of this Skeleton [alias for setCompositeState(~)].
Definition Skeleton.cpp:613
const std::shared_ptr< WholeBodyIK > & createIK()
Create a new WholeBodyIK module for this Skeleton.
Definition Skeleton.cpp:1537
void integratePositions(double _dt)
Definition Skeleton.cpp:1559
dart::common::NameManager< DegreeOfFreedom * > mNameMgrForDofs
NameManager for tracking DegreesOfFreedom.
Definition Skeleton.hpp:1188
void setConfiguration(const Configuration &configuration)
Set the configuration of this Skeleton.
Definition Skeleton.cpp:567
const AspectProperties & getSkeletonProperties() const
Get the Properties of this Skeleton.
Definition Skeleton.cpp:654
void updateTotalMass()
Update the computation for total mass.
Definition Skeleton.cpp:2768
common::aligned_vector< DataCache > mTreeCache
Definition Skeleton.hpp:1304
const std::string & addEntryToBodyNodeNameMgr(BodyNode *_newNode)
Add a BodyNode to the BodyNode NameManager.
Definition Skeleton.cpp:683
std::size_t mUnionSize
Definition Skeleton.hpp:1337
std::size_t mUnionIndex
Definition Skeleton.hpp:1340
const std::vector< BodyNode * > & getTreeBodyNodes(std::size_t _treeIdx)
Get the BodyNodes belonging to a tree in this Skeleton.
Definition Skeleton.cpp:1072
void registerBodyNode(BodyNode *_newBodyNode)
Register a BodyNode with the Skeleton. Internal use only.
Definition Skeleton.cpp:2171
void addEntryToSoftBodyNodeNameMgr(SoftBodyNode *_newNode)
Add a SoftBodyNode to the SoftBodyNode NameManager.
Definition Skeleton.cpp:705
void clearInternalForces() override
Clear the internal forces of the BodyNodes in this MetaSkeleton.
Definition Skeleton.cpp:3776
std::weak_ptr< Skeleton > mUnionRootSkeleton
Definition Skeleton.hpp:1334
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:2086
bool isImpulseApplied() const
Get whether this skeleton is constrained.
Definition Skeleton.cpp:3997
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:3674
double computePotentialEnergy() const override
Get the potential energy of this MetaSkeleton.
Definition Skeleton.cpp:4042
void clearIK()
Wipe away the WholeBodyIK module for this Skeleton, leaving it as a nullptr.
Definition Skeleton.cpp:1544
dart::common::NameManager< Joint * > mNameMgrForJoints
NameManager for tracking Joints.
Definition Skeleton.hpp:1185
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:4193
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:4146
const Eigen::VectorXd & computeConstraintForces(DataCache &cache) const
Compute the constraint force vector for a tree.
Definition Skeleton.cpp:3491
math::Jacobian getJacobianClassicDeriv(const JacobianNode *_node) const override
Get the spatial Jacobian (classical) time derivative targeting the origin of a BodyNode.
Definition Skeleton.cpp:1879
const std::vector< DegreeOfFreedom * > & getDofs() override
Get the vector of DegreesOfFreedom for this MetaSkeleton.
Definition Skeleton.cpp:1233
math::Jacobian getJacobian(const JacobianNode *_node) const override
Get the spatial Jacobian targeting the origin of a BodyNode.
Definition Skeleton.cpp:1698
DataCache mSkelCache
Definition Skeleton.hpp:1306
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:395
Definition Random-impl.hpp:92
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
Definition Memory.hpp:71
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition SmartPointer.hpp:60
std::shared_ptr< MetaSkeleton > MetaSkeletonPtr
Definition SmartPointer.hpp:68
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
std::vector< Eigen::Vector3d > SupportGeometry
Definition Geometry.hpp:504
common::aligned_vector< Eigen::Vector2d > SupportPolygon
Definition Geometry.hpp:506
Definition BulletCollisionDetector.cpp:60
Definition SharedLibraryManager.hpp:46
The Configuration struct represents the joint configuration of a Skeleton.
Definition Skeleton.hpp:96
Eigen::VectorXd mPositions
Joint positions.
Definition Skeleton.hpp:117
bool operator!=(const Configuration &other) const
Inequality comparison operator.
Definition Skeleton.cpp:378
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:114
Eigen::VectorXd mVelocities
Joint velocities.
Definition Skeleton.hpp:120
Eigen::VectorXd mAccelerations
Joint accelerations.
Definition Skeleton.hpp:123
bool operator==(const Configuration &other) const
Equality comparison operator.
Definition Skeleton.cpp:363
Eigen::VectorXd mCommands
Joint commands.
Definition Skeleton.hpp:129
Eigen::VectorXd mForces
Joint forces.
Definition Skeleton.hpp:126
Definition Skeleton.hpp:1240
std::vector< std::size_t > mSupportIndices
A map of which EndEffectors correspond to the individual points in the support polygon.
Definition Skeleton.hpp:1288
Eigen::VectorXd mFext
External force vector for the skeleton.
Definition Skeleton.hpp:1278
std::vector< const DegreeOfFreedom * > mConstDofs
Cache for const Degrees of Freedom, for the sake of the API.
Definition Skeleton.hpp:1253
Eigen::VectorXd mCvec
Coriolis vector for the skeleton which is C(q,dq)*dq.
Definition Skeleton.hpp:1268
Eigen::MatrixXd mInvM
Inverse of mass matrix for the skeleton.
Definition Skeleton.hpp:1262
Eigen::MatrixXd mAugM
Mass matrix for the skeleton.
Definition Skeleton.hpp:1259
Eigen::MatrixXd mInvAugM
Inverse of augmented mass matrix for the skeleton.
Definition Skeleton.hpp:1265
Eigen::VectorXd mG
Gravity vector for the skeleton; computed in nonrecursive dynamics only.
Definition Skeleton.hpp:1272
math::SupportPolygon mSupportPolygon
Support polygon.
Definition Skeleton.hpp:1284
DirtyFlags mDirty
Definition Skeleton.hpp:1241
std::vector< const BodyNode * > mConstBodyNodes
Cache for const BodyNodes, for the sake of the API.
Definition Skeleton.hpp:1247
std::vector< DegreeOfFreedom * > mDofs
Degrees of Freedom belonging to this tree.
Definition Skeleton.hpp:1250
math::SupportGeometry mSupportGeometry
Support geometry – only used for temporary storage purposes.
Definition Skeleton.hpp:1295
Eigen::Vector2d mSupportCentroid
Centroid of the support polygon.
Definition Skeleton.hpp:1298
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:1292
std::vector< BodyNode * > mBodyNodes
BodyNodes belonging to this tree.
Definition Skeleton.hpp:1244
Eigen::VectorXd mFc
Constraint force vector.
Definition Skeleton.hpp:1281
Eigen::MatrixXd mM
Mass matrix cache.
Definition Skeleton.hpp:1256
Eigen::VectorXd mCg
Combined coriolis and gravity vector which is C(q, dq)*dq + g(q).
Definition Skeleton.hpp:1275
Definition Skeleton.hpp:1197
bool mCoriolisForces
Dirty flag for the Coriolis force vector.
Definition Skeleton.hpp:1220
bool mExternalForces
Dirty flag for the external force vector.
Definition Skeleton.hpp:1226
bool mArticulatedInertia
Dirty flag for articulated body inertia.
Definition Skeleton.hpp:1202
bool mInvAugMassMatrix
Dirty flag for the inverse of augmented mass matrix.
Definition Skeleton.hpp:1214
bool mMassMatrix
Dirty flag for the mass matrix.
Definition Skeleton.hpp:1205
bool mAugMassMatrix
Dirty flag for the mass matrix.
Definition Skeleton.hpp:1208
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:1236
bool mSupport
Dirty flag for the support polygon.
Definition Skeleton.hpp:1232
bool mGravityForces
Dirty flag for the gravity force vector.
Definition Skeleton.hpp:1217
bool mDampingForces
Dirty flag for the damping force vector.
Definition Skeleton.hpp:1229
bool mCoriolisAndGravityForces
Dirty flag for the combined vector of Coriolis and gravity.
Definition Skeleton.hpp:1223
bool mInvMassMatrix
Dirty flag for the inverse of mass matrix.
Definition Skeleton.hpp:1211
The Properties of this Skeleton which are independent of the components within the Skeleton,...
Definition SkeletonAspect.hpp:55