33#ifndef DART_DYNAMICS_SKELETON_HPP_
34#define DART_DYNAMICS_SKELETON_HPP_
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());
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());
233 const
std::
string&
setName(const
std::
string& _name) override;
309 template <
typename Jo
intType>
310 static typename JointType::Properties createJointProperties()
312 return typename JointType::Properties();
315 template <
typename NodeType>
316 static typename NodeType::Properties createBodyNodeProperties()
318 return typename NodeType::Properties();
326 template <
class Jo
intType,
class NodeType = BodyNode>
330 const typename JointType::Properties& _jointProperties
331 = Skeleton::createJointProperties<JointType>(),
332 const typename NodeType::Properties& _bodyProperties
333 = Skeleton::createBodyNodeProperties<NodeType>());
335 const typename JointType::Properties& _jointProperties
336 =
typename JointType::Properties(),
337 const typename NodeType::Properties& _bodyProperties
338 =
typename NodeType::Properties());
397 const std::vector<const BodyNode*>&
getBodyNodes()
const override;
412 const std::string&
name)
const override;
442 std::vector<Joint*>
getJoints()
override;
445 std::vector<const Joint*>
getJoints()
const override;
451 std::vector<Joint*>
getJoints(
const std::string&
name)
override;
457 std::vector<const Joint*>
getJoints(
const std::string&
name)
const override;
463 std::size_t
getIndexOf(
const Joint* _joint,
bool _warning=
true)
const override;
481 const std::vector<DegreeOfFreedom*>&
getDofs()
override;
484 std::vector<const DegreeOfFreedom*>
getDofs()
const override;
488 bool _warning=
true)
const override;
491 const std::vector<DegreeOfFreedom*>&
getTreeDofs(std::size_t _treeIdx);
494 const std::vector<const DegreeOfFreedom*>&
getTreeDofs(std::size_t _treeIdx)
const;
504 const std::shared_ptr<WholeBodyIK>&
getIK(
bool _createIfNull =
false);
514 std::shared_ptr<const WholeBodyIK>
getIK()
const;
519 const std::shared_ptr<WholeBodyIK>&
createIK();
548 const Eigen::VectorXd& _q2,
const Eigen::VectorXd& _q1)
const;
554 const Eigen::VectorXd& _dq2,
const Eigen::VectorXd& _dq1)
const;
581 const std::pair<Eigen::Vector3d, Eigen::Vector3d>&
getSupportAxes()
const;
585 const std::pair<Eigen::Vector3d, Eigen::Vector3d>&
getSupportAxes(
586 std::size_t _treeIdx)
const;
643 bool _updateVels =
true,
644 bool _updateAccs =
true);
655 bool _withDampingForces =
false,
656 bool _withSpringForces =
false);
685 PointMass* _pointMass,
686 const Eigen::Vector3d& _imp);
712 const JacobianNode* _node,
713 const Frame* _inCoordinatesOf)
const override;
717 const JacobianNode* _node,
718 const Eigen::Vector3d& _localOffset)
const override;
722 const JacobianNode* _node,
723 const Eigen::Vector3d& _localOffset,
724 const Frame* _inCoordinatesOf)
const override;
728 const JacobianNode* _node)
const override;
732 const JacobianNode* _node,
733 const Eigen::Vector3d& _localOffset)
const override;
737 const JacobianNode* _node,
738 const Frame* _inCoordinatesOf =
Frame::World())
const override;
742 const JacobianNode* _node,
743 const Eigen::Vector3d& _localOffset,
744 const Frame* _inCoordinatesOf =
Frame::World())
const override;
748 const JacobianNode* _node,
749 const Frame* _inCoordinatesOf =
Frame::World())
const override;
753 const JacobianNode* _node)
const override;
757 const JacobianNode* _node,
758 const Frame* _inCoordinatesOf)
const override;
762 const JacobianNode* _node,
763 const Eigen::Vector3d& _localOffset)
const override;
767 const JacobianNode* _node,
768 const Eigen::Vector3d& _localOffset,
769 const Frame* _inCoordinatesOf)
const override;
773 const JacobianNode* _node)
const override;
777 const JacobianNode* _node,
778 const Frame* _inCoordinatesOf)
const override;
782 const JacobianNode* _node,
783 const Eigen::Vector3d& _localOffset,
784 const Frame* _inCoordinatesOf =
Frame::World())
const override;
788 const JacobianNode* _node,
789 const Frame* _inCoordinatesOf =
Frame::World())
const override;
793 const JacobianNode* _node,
794 const Eigen::Vector3d& _localOffset,
795 const Frame* _inCoordinatesOf =
Frame::World())
const override;
799 const JacobianNode* _node,
800 const Frame* _inCoordinatesOf =
Frame::World())
const override;
811 double getMass()
const override;
814 const Eigen::MatrixXd&
getMassMatrix(std::size_t _treeIdx)
const;
910 const Frame* _withRespectTo = Frame::World()) const override;
915 const Frame* _relativeTo = Frame::World(),
916 const Frame* _inCoordinatesOf = Frame::World()) const override;
921 const Frame* _relativeTo = Frame::World(),
922 const Frame* _inCoordinatesOf = Frame::World()) const override;
927 const Frame* _relativeTo = Frame::World(),
928 const Frame* _inCoordinatesOf = Frame::World()) const override;
933 const Frame* _relativeTo = Frame::World(),
934 const Frame* _inCoordinatesOf = Frame::World()) const override;
939 const Frame* _inCoordinatesOf = Frame::World()) const override;
944 const Frame* _inCoordinatesOf = Frame::World()) const override;
953 const Frame* _inCoordinatesOf = Frame::World()) const override;
962 const Frame* _inCoordinatesOf = Frame::World()) const override;
1026 template <class JointType>
1031 const typename JointType::
Properties& _joint);
1036 Joint* _parentJoint,
1040 bool _recursive) const;
1044 template <class JointType>
1049 const typename JointType::
Properties& _joint,
1050 bool _recursive) const;
1271 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#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
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