DART  6.6.2
dart::dynamics::BodyNode Class Reference

BodyNode class represents a single node of the skeleton. More...

#include <BodyNode.hpp>

Inheritance diagram for dart::dynamics::BodyNode:
dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases > dart::dynamics::BodyNodeSpecializedFor< ShapeNode, EndEffector, Marker > dart::dynamics::SkeletonRefCountingBase dart::dynamics::TemplatedJacobianNode< BodyNode > dart::common::CompositeJoiner< EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT >, CompositeBases... > dart::dynamics::JacobianNode dart::dynamics::Frame dart::dynamics::Node dart::dynamics::Entity dart::common::Subject dart::common::VersionCounter dart::common::Subject

Public Types

using ColShapeAddedSignal = common::Signal< void(const BodyNode *, ConstShapePtr _newColShape)>
 
using ColShapeRemovedSignal = ColShapeAddedSignal
 
using StructuralChangeSignal = common::Signal< void(const BodyNode *)>
 
using CompositeProperties = common::Composite::Properties
 
using AllNodeStates = detail::AllNodeStates
 
using NodeStateMap = detail::NodeStateMap
 
using AllNodeProperties = detail::AllNodeProperties
 
using NodePropertiesMap = detail::NodePropertiesMap
 
using AspectProperties = detail::BodyNodeAspectProperties
 
using Properties = common::Composite::MakeProperties< BodyNode >
 
using Impl = EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT >
 
using Derived = typename Impl::Derived
 
using AspectStateData = typename Impl::AspectStateData
 
using AspectState = typename Impl::AspectState
 
using AspectPropertiesData = typename Impl::AspectPropertiesData
 
using Aspect = typename Impl::Aspect
 
using Base = CompositeJoiner< Impl, CompositeBases... >
 
using EntitySignal = common::Signal< void(const Entity *)>
 
using FrameChangedSignal = common::Signal< void(const Entity *, const Frame *_oldFrame, const Frame *_newFrame)>
 
using NameChangedSignal = common::Signal< void(const Entity *, const std::string &_oldName, const std::string &_newName)>
 
template<class Mixin >
using MakeState = common::MakeCloneable< State, Mixin >
 Use the MakeState class to easily create a State extension from an existing class or struct. More...
 
template<class Mixin >
using MakeProperties = common::MakeCloneable< Properties, Mixin >
 Use the MakeProperties class to easily create a Properties extension from an existing class or struct. More...
 

Public Member Functions

 BodyNode (const BodyNode &)=delete
 
virtual ~BodyNode ()
 Destructor. More...
 
virtual SoftBodyNodeasSoftBodyNode ()
 Convert 'this' into a SoftBodyNode pointer if this BodyNode is a SoftBodyNode, otherwise return nullptr. More...
 
virtual const SoftBodyNodeasSoftBodyNode () const
 Convert 'const this' into a SoftBodyNode pointer if this BodyNode is a SoftBodyNode, otherwise return nullptr. More...
 
void setAllNodeStates (const AllNodeStates &states)
 Set the Node::State of all Nodes attached to this BodyNode. More...
 
AllNodeStates getAllNodeStates () const
 Get the Node::State of all Nodes attached to this BodyNode. More...
 
void setAllNodeProperties (const AllNodeProperties &properties)
 Set the Node::Properties of all Nodes attached to this BodyNode. More...
 
AllNodeProperties getAllNodeProperties () const
 Get the Node::Properties of all Nodes attached to this BodyNode. More...
 
void setProperties (const CompositeProperties &_properties)
 Same as setCompositeProperties() More...
 
void setProperties (const AspectProperties &_properties)
 Set the UniqueProperties of this BodyNode. More...
 
void setAspectState (const AspectState &state)
 Set the AspectState of this BodyNode. More...
 
void setAspectProperties (const AspectProperties &properties)
 Set the AspectProperties of this BodyNode. More...
 
Properties getBodyNodeProperties () const
 Get the Properties of this BodyNode. More...
 
void copy (const BodyNode &otherBodyNode)
 Copy the Properties of another BodyNode. More...
 
void copy (const BodyNode *otherBodyNode)
 Copy the Properties of another BodyNode. More...
 
BodyNodeoperator= (const BodyNode &_otherBodyNode)
 Same as copy(const BodyNode&) More...
 
void duplicateNodes (const BodyNode *otherBodyNode)
 Give this BodyNode a copy of each Node from otherBodyNode. More...
 
void matchNodes (const BodyNode *otherBodyNode)
 Make the Nodes of this BodyNode match the Nodes of otherBodyNode. More...
 
const std::string & setName (const std::string &_name) override
 Set name. More...
 
const std::string & getName () const override
 Get the name of this Node. More...
 
void setGravityMode (bool _gravityMode)
 Set whether gravity affects this body. More...
 
bool getGravityMode () const
 Return true if gravity mode is enabled. More...
 
bool isCollidable () const
 Return true if this body can collide with others bodies. More...
 
void setCollidable (bool _isCollidable)
 Set whether this body node will collide with others in the world. More...
 
void setMass (double mass)
 Set the mass of the bodynode. More...
 
double getMass () const
 Return the mass of the bodynode. More...
 
void setMomentOfInertia (double _Ixx, double _Iyy, double _Izz, double _Ixy=0.0, double _Ixz=0.0, double _Iyz=0.0)
 Set moment of inertia defined around the center of mass. More...
 
void getMomentOfInertia (double &_Ixx, double &_Iyy, double &_Izz, double &_Ixy, double &_Ixz, double &_Iyz) const
 Return moment of inertia defined around the center of mass. More...
 
const Eigen::Matrix6dgetSpatialInertia () const
 Return spatial inertia. More...
 
void setInertia (const Inertia &inertia)
 Set the inertia data for this BodyNode. More...
 
const InertiagetInertia () const
 Get the inertia data for this BodyNode. More...
 
const math::InertiagetArticulatedInertia () const
 Return the articulated body inertia. More...
 
const math::InertiagetArticulatedInertiaImplicit () const
 Return the articulated body inertia for implicit joint damping and spring forces. More...
 
void setLocalCOM (const Eigen::Vector3d &_com)
 Set center of mass expressed in body frame. More...
 
const Eigen::Vector3d & getLocalCOM () const
 Return center of mass expressed in body frame. More...
 
Eigen::Vector3d getCOM (const Frame *_withRespectTo=Frame::World()) const
 Return the center of mass with respect to an arbitrary Frame. More...
 
Eigen::Vector3d getCOMLinearVelocity (const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Return the linear velocity of the center of mass, expressed in terms of arbitrary Frames. More...
 
Eigen::Vector6d getCOMSpatialVelocity () const
 Return the spatial velocity of the center of mass, expressed in coordinates of this Frame and relative to the World Frame. More...
 
Eigen::Vector6d getCOMSpatialVelocity (const Frame *_relativeTo, const Frame *_inCoordinatesOf) const
 Return the spatial velocity of the center of mass, expressed in terms of arbitrary Frames. More...
 
Eigen::Vector3d getCOMLinearAcceleration (const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Return the linear acceleration of the center of mass, expressed in terms of arbitary Frames. More...
 
Eigen::Vector6d getCOMSpatialAcceleration () const
 Return the acceleration of the center of mass expressed in coordinates of this BodyNode Frame and relative to the World Frame. More...
 
Eigen::Vector6d getCOMSpatialAcceleration (const Frame *_relativeTo, const Frame *_inCoordinatesOf) const
 Return the spatial acceleration of the center of mass, expressed in terms of arbitrary Frames. More...
 
void setFrictionCoeff (double _coeff)
 Set coefficient of friction in range of [0, ~]. More...
 
double getFrictionCoeff () const
 Return frictional coefficient. More...
 
void setRestitutionCoeff (double _coeff)
 Set coefficient of restitution in range of [0, 1]. More...
 
double getRestitutionCoeff () const
 Return coefficient of restitution. More...
 
std::size_t getIndexInSkeleton () const
 Return the index of this BodyNode within its Skeleton. More...
 
std::size_t getIndexInTree () const
 Return the index of this BodyNode within its tree. More...
 
std::size_t getTreeIndex () const
 Return the index of the tree that this BodyNode belongs to. More...
 
SkeletonPtr remove (const std::string &_name="temporary")
 Remove this BodyNode and all of its children (recursively) from their Skeleton. More...
 
bool moveTo (BodyNode *_newParent)
 Remove this BodyNode and all of its children (recursively) from their current parent BodyNode, and move them to another parent BodyNode. More...
 
bool moveTo (const SkeletonPtr &_newSkeleton, BodyNode *_newParent)
 This is a version of moveTo(BodyNode*) that allows you to explicitly move this BodyNode into a different Skeleton. More...
 
template<class JointType >
JointType * moveTo (BodyNode *_newParent, const typename JointType::Properties &_joint=typename JointType::Properties())
 A version of moveTo(BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode. More...
 
template<class JointType >
JointType * moveTo (const SkeletonPtr &_newSkeleton, BodyNode *_newParent, const typename JointType::Properties &_joint=typename JointType::Properties())
 A version of moveTo(SkeletonPtr, BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode. More...
 
SkeletonPtr split (const std::string &_skeletonName)
 Remove this BodyNode and all of its children (recursively) from their current Skeleton and move them into a newly created Skeleton. More...
 
template<class JointType >
SkeletonPtr split (const std::string &_skeletonName, const typename JointType::Properties &_joint=typename JointType::Properties())
 A version of split(const std::string&) that also changes the Joint type of the parent Joint of this BodyNode. More...
 
template<class JointType >
JointType * changeParentJointType (const typename JointType::Properties &_joint=typename JointType::Properties())
 Change the Joint type of this BodyNode's parent Joint. More...
 
std::pair< Joint *, BodyNode * > copyTo (BodyNode *_newParent, bool _recursive=true)
 Create clones of this BodyNode and all of its children recursively (unless _recursive is set to false) and attach the clones to the specified BodyNode. More...
 
std::pair< Joint *, BodyNode * > copyTo (const SkeletonPtr &_newSkeleton, BodyNode *_newParent, bool _recursive=true) const
 Create clones of this BodyNode and all of its children recursively (unless recursive is set to false) and attach the clones to the specified BodyNode of the specified Skeleton. More...
 
template<class JointType >
std::pair< JointType *, BodyNode * > copyTo (BodyNode *_newParent, const typename JointType::Properties &_joint=typename JointType::Properties(), bool _recursive=true)
 A version of copyTo(BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode. More...
 
template<class JointType >
std::pair< JointType *, BodyNode * > copyTo (const SkeletonPtr &_newSkeleton, BodyNode *_newParent, const typename JointType::Properties &_joint=typename JointType::Properties(), bool _recursive=true) const
 A version of copyTo(Skeleton*,BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode. More...
 
SkeletonPtr copyAs (const std::string &_skeletonName, bool _recursive=true) const
 Create clones of this BodyNode and all of its children (recursively) and create a new Skeleton with the specified name to attach them to. More...
 
template<class JointType >
SkeletonPtr copyAs (const std::string &_skeletonName, const typename JointType::Properties &_joint=typename JointType::Properties(), bool _recursive=true) const
 A version of copyAs(const std::string&) that also changes the Joint type of the root BodyNode. More...
 
SkeletonPtr getSkeleton () override
 Return the Skeleton that this Node is attached to. More...
 
ConstSkeletonPtr getSkeleton () const override
 Return the Skeleton that this Node is attached to. More...
 
JointgetParentJoint ()
 Return the parent Joint of this BodyNode. More...
 
const JointgetParentJoint () const
 Return the (const) parent Joint of this BodyNode. More...
 
BodyNodegetParentBodyNode ()
 Return the parent BodyNdoe of this BodyNode. More...
 
const BodyNodegetParentBodyNode () const
 Return the (const) parent BodyNode of this BodyNode. More...
 
template<class JointType , class NodeType = BodyNode>
std::pair< JointType *, NodeType * > createChildJointAndBodyNodePair (const typename JointType::Properties &_jointProperties=typename JointType::Properties(), const typename NodeType::Properties &_bodyProperties=typename NodeType::Properties())
 Create a Joint and BodyNode pair as a child of this BodyNode. More...
 
std::size_t getNumChildBodyNodes () const
 Return the number of child BodyNodes. More...
 
BodyNodegetChildBodyNode (std::size_t _index)
 Return the _index-th child BodyNode of this BodyNode. More...
 
const BodyNodegetChildBodyNode (std::size_t _index) const
 Return the (const) _index-th child BodyNode of this BodyNode. More...
 
std::size_t getNumChildJoints () const
 Return the number of child Joints. More...
 
JointgetChildJoint (std::size_t _index)
 Return the _index-th child Joint of this BodyNode. More...
 
const JointgetChildJoint (std::size_t _index) const
 Return the (const) _index-th child Joint of this BodyNode. More...
 
template<class NodeType , typename ... Args>
NodeType * createNode (Args &&... args)
 Create some Node type and attach it to this BodyNode. More...
 
std::size_t getNumShapeNodes () const
 
ShapeNodegetShapeNode (std::size_t index)
 
const ShapeNodegetShapeNode (std::size_t index) const
 
template<class ShapeNodeProperties >
ShapeNodecreateShapeNode (ShapeNodeProperties properties, bool automaticName=true)
 Create an ShapeNode attached to this BodyNode. More...
 
template<class ShapeType >
ShapeNodecreateShapeNode (const std::shared_ptr< ShapeType > &shape)
 Create a ShapeNode with an automatically assigned name: <BodyNodeName>ShapeNode<#>. More...
 
template<class ShapeType , class StringType >
ShapeNodecreateShapeNode (const std::shared_ptr< ShapeType > &shape, StringType &&name)
 Create a ShapeNode with the specified name. More...
 
const std::vector< ShapeNode * > getShapeNodes ()
 Return the list of ShapeNodes. More...
 
const std::vector< const ShapeNode * > getShapeNodes () const
 Return the list of (const) ShapeNodes. More...
 
void removeAllShapeNodes ()
 Remove all ShapeNodes from this BodyNode. More...
 
template<class... Aspects>
ShapeNodecreateShapeNodeWith (const ShapePtr &shape)
 Create a ShapeNode with the specified Aspects and an automatically assigned name: <BodyNodeName>ShapeNode<#>. More...
 
template<class... Aspects>
ShapeNodecreateShapeNodeWith (const ShapePtr &shape, const std::string &name)
 Create a ShapeNode with the specified name and Aspects. More...
 
template<class Aspect >
std::size_t getNumShapeNodesWith () const
 Return the number of ShapeNodes containing given Aspect in this BodyNode. More...
 
template<class Aspect >
const std::vector< ShapeNode * > getShapeNodesWith ()
 Return the list of ShapeNodes containing given Aspect. More...
 
template<class Aspect >
const std::vector< const ShapeNode * > getShapeNodesWith () const
 Return the list of ShapeNodes containing given Aspect. More...
 
template<class Aspect >
void removeAllShapeNodesWith ()
 Remove all ShapeNodes containing given Aspect from this BodyNode. More...
 
std::size_t getNumEndEffectors () const
 
EndEffectorgetEndEffector (std::size_t index)
 
const EndEffectorgetEndEffector (std::size_t index) const
 
EndEffectorcreateEndEffector (const EndEffector::BasicProperties &_properties)
 Create an EndEffector attached to this BodyNode. More...
 
EndEffectorcreateEndEffector (const std::string &_name="EndEffector")
 Create an EndEffector with the specified name. More...
 
EndEffectorcreateEndEffector (const char *_name)
 Create an EndEffector with the specified name. More...
 
std::size_t getNumMarkers () const
 
MarkergetMarker (std::size_t index)
 
const MarkergetMarker (std::size_t index) const
 
MarkercreateMarker (const std::string &name="marker", const Eigen::Vector3d &position=Eigen::Vector3d::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d::Constant(1.0))
 Create a Marker with the given fields. More...
 
MarkercreateMarker (const Marker::BasicProperties &properties)
 Create a Marker given its basic properties. More...
 
bool dependsOn (std::size_t _genCoordIndex) const override
 Return true if _genCoordIndex-th generalized coordinate. More...
 
std::size_t getNumDependentGenCoords () const override
 The number of the generalized coordinates which affect this JacobianNode. More...
 
std::size_t getDependentGenCoordIndex (std::size_t _arrayIndex) const override
 Return a generalized coordinate index from the array index (< getNumDependentDofs) More...
 
const std::vector< std::size_t > & getDependentGenCoordIndices () const override
 Indices of the generalized coordinates which affect this JacobianNode. More...
 
std::size_t getNumDependentDofs () const override
 Same as getNumDependentGenCoords() More...
 
DegreeOfFreedomgetDependentDof (std::size_t _index) override
 Get a pointer to the _indexth dependent DegreeOfFreedom for this BodyNode. More...
 
const DegreeOfFreedomgetDependentDof (std::size_t _index) const override
 Get a pointer to the _indexth dependent DegreeOfFreedom for this BodyNode. More...
 
const std::vector< DegreeOfFreedom * > & getDependentDofs () override
 Return a std::vector of DegreeOfFreedom pointers that this Node depends on. More...
 
const std::vector< const DegreeOfFreedom * > & getDependentDofs () const override
 Return a std::vector of DegreeOfFreedom pointers that this Node depends on. More...
 
const std::vector< const DegreeOfFreedom * > getChainDofs () const override
 Returns a DegreeOfFreedom vector containing the dofs that form a Chain leading up to this JacobianNode from the root of the Skeleton. More...
 
const Eigen::Isometry3d & getRelativeTransform () const override
 Get the transform of this BodyNode with respect to its parent BodyNode, which is also its parent Frame. More...
 
const Eigen::Vector6dgetRelativeSpatialVelocity () const override
 Get the spatial velocity of this Frame relative to its parent Frame, in its own coordinates. More...
 
const Eigen::Vector6dgetRelativeSpatialAcceleration () const override
 Get the spatial acceleration of this Frame relative to its parent Frame, in the coordinates of this Frame. More...
 
const Eigen::Vector6dgetPrimaryRelativeAcceleration () const override
 The Featherstone ABI algorithm exploits a component of the spatial acceleration which we refer to as the partial acceleration, accessible by getPartialAcceleration(). More...
 
const Eigen::Vector6dgetPartialAcceleration () const override
 Return the partial acceleration of this body. More...
 
const math::JacobiangetJacobian () const override final
 Return the generalized Jacobian targeting the origin of this BodyNode. More...
 
const math::JacobiangetWorldJacobian () const override final
 Return the generalized Jacobian targeting the origin of this BodyNode. More...
 
const math::JacobiangetJacobianSpatialDeriv () const override final
 Return the spatial time derivative of the generalized Jacobian targeting the origin of this BodyNode. More...
 
const math::JacobiangetJacobianClassicDeriv () const override final
 Return the classical time derivative of the generalized Jacobian targeting the origin of this BodyNode. More...
 
const Eigen::Vector6dgetBodyVelocityChange () const
 Return the velocity change due to the constraint impulse. More...
 
void setColliding (bool _isColliding)
 Set whether this body node is colliding with other objects. More...
 
bool isColliding ()
 Return whether this body node is set to be colliding with other objects. More...
 
void addExtForce (const Eigen::Vector3d &_force, const Eigen::Vector3d &_offset=Eigen::Vector3d::Zero(), bool _isForceLocal=false, bool _isOffsetLocal=true)
 Add applying linear Cartesian forces to this node. More...
 
void setExtForce (const Eigen::Vector3d &_force, const Eigen::Vector3d &_offset=Eigen::Vector3d::Zero(), bool _isForceLocal=false, bool _isOffsetLocal=true)
 Set Applying linear Cartesian forces to this node. More...
 
void addExtTorque (const Eigen::Vector3d &_torque, bool _isLocal=false)
 Add applying Cartesian torque to the node. More...
 
void setExtTorque (const Eigen::Vector3d &_torque, bool _isLocal=false)
 Set applying Cartesian torque to the node. More...
 
virtual void clearExternalForces ()
 Clean up structures that store external forces: mContacts, mFext, mExtForceBody and mExtTorqueBody. More...
 
virtual void clearInternalForces ()
 Clear out the generalized forces of the parent Joint and any other forces related to this BodyNode that are internal to the Skeleton. More...
 
const Eigen::Vector6dgetExternalForceLocal () const
 
Eigen::Vector6d getExternalForceGlobal () const
 
const Eigen::Vector6dgetBodyForce () const
 Get spatial body force transmitted from the parent joint. More...
 
bool isReactive () const
 Return true if the body can react to force or constraint impulse. More...
 
void setConstraintImpulse (const Eigen::Vector6d &_constImp)
 Set constraint impulse. More...
 
void addConstraintImpulse (const Eigen::Vector6d &_constImp)
 Add constraint impulse. More...
 
void addConstraintImpulse (const Eigen::Vector3d &_constImp, const Eigen::Vector3d &_offset, bool _isImpulseLocal=false, bool _isOffsetLocal=true)
 Add constraint impulse. More...
 
virtual void clearConstraintImpulse ()
 Clear constraint impulses and cache data used for impulse-based forward dynamics algorithm. More...
 
const Eigen::Vector6dgetConstraintImpulse () const
 Return constraint impulse. More...
 
double computeLagrangian (const Eigen::Vector3d &gravity) const
 Return Lagrangian of this body. More...
 
virtual double getKineticEnergy () const
 Return kinetic energy. More...
 
double computeKineticEnergy () const
 Return kinetic energy. More...
 
virtual double getPotentialEnergy (const Eigen::Vector3d &_gravity) const
 Return potential energy. More...
 
double computePotentialEnergy (const Eigen::Vector3d &gravity) const
 Return potential energy. More...
 
Eigen::Vector3d getLinearMomentum () const
 Return linear momentum. More...
 
Eigen::Vector3d getAngularMomentum (const Eigen::Vector3d &_pivot=Eigen::Vector3d::Zero())
 Return angular momentum. More...
 
void dirtyTransform () override
 Notify the transformation updates of this Frame and all its children are needed. More...
 
void dirtyVelocity () override
 Notify the velocity updates of this Frame and all its children are needed. More...
 
void dirtyAcceleration () override
 Notify the acceleration updates of this Frame and all its children are needed. More...
 
void notifyArticulatedInertiaUpdate ()
 Notify the Skeleton that the tree of this BodyNode needs an articulated inertia update. More...
 
void dirtyArticulatedInertia ()
 Notify the Skeleton that the tree of this BodyNode needs an articulated inertia update. More...
 
void notifyExternalForcesUpdate ()
 Tell the Skeleton that the external forces need to be updated. More...
 
void dirtyExternalForces ()
 Tell the Skeleton that the external forces need to be updated. More...
 
void notifyCoriolisUpdate ()
 Tell the Skeleton that the coriolis forces need to be update. More...
 
void dirtyCoriolisForces ()
 Tell the Skeleton that the coriolis forces need to be update. More...
 
const AspectStategetAspectState () const
 
const AspectPropertiesgetAspectProperties () const
 
math::Jacobian getJacobian (const Frame *_inCoordinatesOf) const override final
 A version of getJacobian() that lets you specify a coordinate Frame to express the Jacobian in. More...
 
math::Jacobian getJacobian (const Eigen::Vector3d &_offset) const override final
 Return the generalized Jacobian targeting an offset within the Frame of this JacobianNode. More...
 
math::Jacobian getJacobian (const Eigen::Vector3d &_offset, const Frame *_inCoordinatesOf) const override final
 A version of getJacobian(const Eigen::Vector3d&) that lets you specify a coordinate Frame to express the Jacobian in. More...
 
math::Jacobian getWorldJacobian (const Eigen::Vector3d &_offset) const override final
 Return the generalized Jacobian targeting an offset in this JacobianNode. More...
 
math::LinearJacobian getLinearJacobian (const Frame *_inCoordinatesOf=Frame::World()) const override final
 Return the linear Jacobian targeting the origin of this BodyNode. More...
 
math::LinearJacobian getLinearJacobian (const Eigen::Vector3d &_offset, const Frame *_inCoordinatesOf=Frame::World()) const override final
 Return the generalized Jacobian targeting an offset within the Frame of this BodyNode. More...
 
math::AngularJacobian getAngularJacobian (const Frame *_inCoordinatesOf=Frame::World()) const override final
 Return the angular Jacobian targeting the origin of this BodyNode. More...
 
math::Jacobian getJacobianSpatialDeriv (const Frame *_inCoordinatesOf) const override final
 A version of getJacobianSpatialDeriv() that can return the Jacobian in coordinates of any Frame. More...
 
math::Jacobian getJacobianSpatialDeriv (const Eigen::Vector3d &_offset) const override final
 Return the spatial time derivative of the generalized Jacobian targeting an offset in the Frame of this BodyNode. More...
 
math::Jacobian getJacobianSpatialDeriv (const Eigen::Vector3d &_offset, const Frame *_inCoordinatesOf) const override final
 A version of getJacobianSpatialDeriv(const Eigen::Vector3d&) that allows an arbitrary coordinate Frame to be specified. More...
 
math::Jacobian getJacobianClassicDeriv (const Frame *_inCoordinatesOf) const override final
 A version of getJacobianClassicDeriv() that can return the Jacobian in coordinates of any Frame. More...
 
math::Jacobian getJacobianClassicDeriv (const Eigen::Vector3d &_offset, const Frame *_inCoordinatesOf=Frame::World()) const override final
 A version of getJacobianClassicDeriv() that can compute the Jacobian for an offset within the Frame of this BodyNode. More...
 
math::LinearJacobian getLinearJacobianDeriv (const Frame *_inCoordinatesOf=Frame::World()) const override final
 Return the linear Jacobian (classical) time derivative, in terms of any coordinate Frame. More...
 
math::LinearJacobian getLinearJacobianDeriv (const Eigen::Vector3d &_offset, const Frame *_inCoordinatesOf=Frame::World()) const override final
 A version of getLinearJacobianDeriv() that can compute the Jacobian for an offset within the Frame of this BodyNode. More...
 
math::AngularJacobian getAngularJacobianDeriv (const Frame *_inCoordinatesOf=Frame::World()) const override final
 Return the angular Jacobian time derivative, in terms of any coordinate Frame. More...
 
const std::shared_ptr< InverseKinematics > & getIK (bool _createIfNull=false)
 Get a pointer to an IK module for this JacobianNode. More...
 
std::shared_ptr< const InverseKinematicsgetIK () const
 Get a pointer to an IK module for this JacobianNode. More...
 
const std::shared_ptr< InverseKinematics > & getOrCreateIK ()
 Get a pointer to an IK module for this JacobianNode. More...
 
const std::shared_ptr< InverseKinematics > & createIK ()
 Create a new IK module for this JacobianNode. More...
 
void clearIK ()
 Wipe away the IK module for this JacobianNode, leaving it as a nullptr. More...
 
void notifyJacobianUpdate ()
 Notify this BodyNode and all its descendents that their Jacobians need to be updated. More...
 
void dirtyJacobian ()
 Notify this BodyNode and all its descendents that their Jacobians need to be updated. More...
 
void notifyJacobianDerivUpdate ()
 Notify this BodyNode and all its descendents that their Jacobian derivatives need to be updated. More...
 
void dirtyJacobianDeriv ()
 Notify this BodyNode and all its descendents that their Jacobian derivatives need to be updated. More...
 
virtual const std::string & setName (const std::string &newName)=0
 Set the name of this Node. More...
 
virtual const std::string & getName () const=0
 Get the name of this Node. More...
 
const Eigen::Isometry3d & getWorldTransform () const
 Get the transform of this Frame with respect to the World Frame. More...
 
Eigen::Isometry3d getTransform (const Frame *_withRespectTo=Frame::World()) const
 Get the transform of this Frame with respect to some other Frame. More...
 
Eigen::Isometry3d getTransform (const Frame *withRespectTo, const Frame *inCoordinatesOf) const
 Get the transform of this Frame with respect to some other Frame. More...
 
const Eigen::Vector6dgetSpatialVelocity () const
 Get the total spatial velocity of this Frame in the coordinates of this Frame. More...
 
Eigen::Vector6d getSpatialVelocity (const Frame *_relativeTo, const Frame *_inCoordinatesOf) const
 Get the spatial velocity of this Frame relative to some other Frame. More...
 
Eigen::Vector6d getSpatialVelocity (const Eigen::Vector3d &_offset) const
 Get the spatial velocity of a fixed point in this Frame. More...
 
Eigen::Vector6d getSpatialVelocity (const Eigen::Vector3d &_offset, const Frame *_relativeTo, const Frame *_inCoordinatesOf) const
 Get the spatial velocity of a fixed point in this Frame. More...
 
Eigen::Vector3d getLinearVelocity (const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Get the linear portion of classical velocity of this Frame relative to some other Frame. More...
 
Eigen::Vector3d getLinearVelocity (const Eigen::Vector3d &_offset, const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Get the linear velocity of a point that is fixed in this Frame. More...
 
Eigen::Vector3d getAngularVelocity (const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Get the angular portion of classical velocity of this Frame relative to some other Frame. More...
 
const Eigen::Vector6dgetSpatialAcceleration () const
 Get the total spatial acceleration of this Frame in the coordinates of this Frame. More...
 
Eigen::Vector6d getSpatialAcceleration (const Frame *_relativeTo, const Frame *_inCoordinatesOf) const
 Get the spatial acceleration of this Frame relative to some other Frame. More...
 
Eigen::Vector6d getSpatialAcceleration (const Eigen::Vector3d &_offset) const
 Get the spatial acceleration of a fixed point in this Frame. More...
 
Eigen::Vector6d getSpatialAcceleration (const Eigen::Vector3d &_offset, const Frame *_relativeTo, const Frame *_inCoordinatesOf) const
 Get the spatial acceleration of a fixed point in this Frame. More...
 
Eigen::Vector3d getLinearAcceleration (const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Get the linear portion of classical acceleration of this Frame relative to some other Frame. More...
 
Eigen::Vector3d getLinearAcceleration (const Eigen::Vector3d &_offset, const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 
Eigen::Vector3d getAngularAcceleration (const Frame *_relativeTo=Frame::World(), const Frame *_inCoordinatesOf=Frame::World()) const
 Get the angular portion of classical acceleration of this Frame relative to some other Frame. More...
 
const std::set< Entity * > & getChildEntities ()
 Get a container with the Entities that are children of this Frame. More...
 
const std::set< const Entity * > getChildEntities () const
 Get a container with the Entities that are children of this Frame. More...
 
std::size_t getNumChildEntities () const
 Get the number of Entities that are currently children of this Frame. More...
 
const std::set< Frame * > & getChildFrames ()
 Get a container with the Frames that are children of this Frame. More...
 
std::set< const Frame * > getChildFrames () const
 Get a container with the Frames that are children of this Frame. More...
 
std::size_t getNumChildFrames () const
 Get the number of Frames that are currently children of this Frame. More...
 
bool isShapeFrame () const
 Returns true if this Frame is a ShapeFrame. More...
 
virtual ShapeFrameasShapeFrame ()
 Convert 'this' into a ShapeFrame pointer if Frame is a ShapeFrame, otherwise return nullptr. More...
 
virtual const ShapeFrameasShapeFrame () const
 Convert 'const this' into a ShapeFrame pointer if Frame is a ShapeFrame, otherwise return nullptr. More...
 
bool isWorld () const
 Returns true if this Frame is the World Frame. More...
 
FramegetParentFrame ()
 Get the parent (reference) frame of this Entity. More...
 
const FramegetParentFrame () const
 Get the parent (reference) frame of this Entity. More...
 
bool descendsFrom (const Frame *_someFrame) const
 True if and only if this Entity depends on (i.e. More...
 
bool isFrame () const
 True iff this Entity is also a Frame. More...
 
bool isQuiet () const
 Returns true if this Entity is set to be quiet. More...
 
virtual void notifyTransformUpdate ()
 Notify the transformation update of this Entity that its parent Frame's pose is needed. More...
 
bool needsTransformUpdate () const
 Returns true iff a transform update is needed for this Entity. More...
 
virtual void notifyVelocityUpdate ()
 Notify the velocity update of this Entity that its parent Frame's velocity is needed. More...
 
bool needsVelocityUpdate () const
 Returns true iff a velocity update is needed for this Entity. More...
 
virtual void notifyAccelerationUpdate ()
 Notify the acceleration of this Entity that its parent Frame's acceleration is needed. More...
 
bool needsAccelerationUpdate () const
 Returns true iff an acceleration update is needed for this Entity. More...
 
virtual void setNodeState (const State &otherState)
 Set the State of this Node. By default, this does nothing. More...
 
virtual std::unique_ptr< StategetNodeState () const
 Get the State of this Node. More...
 
virtual void copyNodeStateTo (std::unique_ptr< State > &outputState) const
 Copy the State of this Node into a unique_ptr. More...
 
virtual void setNodeProperties (const Properties &properties)
 Set the Properties of this Node. By default, this does nothing. More...
 
virtual std::unique_ptr< PropertiesgetNodeProperties () const
 Get the Properties of this Node. More...
 
virtual void copyNodePropertiesTo (std::unique_ptr< Properties > &outputProperties) const
 Copy the Properties of this Node into a unique_ptr. More...
 
BodyNodePtr getBodyNodePtr ()
 Get a pointer to the BodyNode that this Node is associated with. More...
 
ConstBodyNodePtr getBodyNodePtr () const
 Get a pointer to the BodyNode that this Node is associated with. More...
 
bool isRemoved () const
 Returns true if this Node has been staged for removal from its BodyNode. More...
 
virtual std::size_t incrementVersion ()
 Increment the version for this object. More...
 
virtual std::size_t getVersion () const
 Get the version number of this object. More...
 

Static Public Member Functions

static FrameWorld ()
 

Public Attributes

Slot registers
common::SlotRegister< ColShapeAddedSignalonColShapeAdded
 Slot register for collision shape added signal. More...
 
common::SlotRegister< ColShapeRemovedSignalonColShapeRemoved
 Slot register for collision shape removed signal. More...
 
common::SlotRegister< StructuralChangeSignalonStructuralChange
 Raised when (1) parent BodyNode is changed, (2) moved between Skeletons, (3) parent Joint is changed. More...
 

Protected Types

enum  ConstructAbstractTag { ConstructAbstract }
 Used when constructing a pure abstract class, because calling the Frame constructor is just a formality. More...
 
enum  ConstructFrameTag { ConstructFrame }
 Used when constructing a Frame class, because the Frame constructor will take care of setting up the parameters you pass into it. More...
 

Protected Member Functions

 BodyNode (BodyNode *_parentBodyNode, Joint *_parentJoint, const Properties &_properties)
 Constructor called by Skeleton class. More...
 
 BodyNode (const std::tuple< BodyNode *, Joint *, Properties > &args)
 Delegating constructor. More...
 
virtual BodyNodeclone (BodyNode *_parentBodyNode, Joint *_parentJoint, bool cloneNodes) const
 Create a clone of this BodyNode. More...
 
NodecloneNode (BodyNode *bn) const override final
 This is needed in order to inherit the Node class, but it does nothing. More...
 
virtual void init (const SkeletonPtr &_skeleton)
 Initialize the vector members with proper sizes. More...
 
void addChildBodyNode (BodyNode *_body)
 Add a child bodynode into the bodynode. More...
 
virtual void changeParentFrame (Frame *_newParentFrame) override
 Used by derived classes to change their parent frames. More...
 
void sendDestructionNotification () const
 Send a destruction notification to all Observers. More...
 
void addObserver (Observer *_observer) const
 Add an Observer to the list of Observers. More...
 
void removeObserver (Observer *_observer) const
 Remove an Observer from the list of Observers. More...
 
std::string registerNameChange (const std::string &newName)
 Inform the Skeleton that the name of this Node has changed. More...
 
void attach ()
 Attach the Node to its BodyNode. More...
 
void stageForRemoval ()
 When all external references to the Node disappear, it will be deleted. More...
 
void setVersionDependentObject (VersionCounter *dependent)
 
Recursive dynamics routines
void processNewEntity (Entity *_newChildEntity) override
 Separate generic child Entities from child BodyNodes for more efficient update notices. More...
 
void processRemovedEntity (Entity *_oldChildEntity) override
 Remove this Entity from mChildBodyNodes or mNonBodyNodeEntities. More...
 
virtual void updateTransform ()
 Update transformation. More...
 
virtual void updateVelocity ()
 Update spatial body velocity. More...
 
virtual void updatePartialAcceleration () const
 Update partial spatial body acceleration due to parent joint's velocity. More...
 
virtual void updateArtInertia (double _timeStep) const
 Update articulated body inertia for forward dynamics. More...
 
virtual void updateBiasForce (const Eigen::Vector3d &_gravity, double _timeStep)
 Update bias force associated with the articulated body inertia for forward dynamics. More...
 
virtual void updateBiasImpulse ()
 Update bias impulse associated with the articulated body inertia for impulse-based forward dynamics. More...
 
virtual void updateAccelerationID ()
 Update spatial body acceleration with the partial spatial body acceleration for inverse dynamics. More...
 
virtual void updateAccelerationFD ()
 Update spatial body acceleration for forward dynamics. More...
 
virtual void updateVelocityChangeFD ()
 Update spatical body velocity change for impluse-based forward dynamics. More...
 
virtual void updateTransmittedForceID (const Eigen::Vector3d &_gravity, bool _withExternalForces=false)
 Update spatial body force for inverse dynamics. More...
 
virtual void updateTransmittedForceFD ()
 Update spatial body force for forward dynamics. More...
 
virtual void updateTransmittedImpulse ()
 Update spatial body force for impulse-based forward dynamics. More...
 
virtual void updateJointForceID (double _timeStep, bool _withDampingForces, bool _withSpringForces)
 Update the joint force for inverse dynamics. More...
 
virtual void updateJointForceFD (double _timeStep, bool _withDampingForces, bool _withSpringForces)
 Update the joint force for forward dynamics. More...
 
virtual void updateJointImpulseFD ()
 Update the joint impulse for forward dynamics. More...
 
virtual void updateConstrainedTerms (double _timeStep)
 Update constrained terms due to the constraint impulses for foward dynamics. More...
 
Equations of motion related routines
virtual void updateMassMatrix ()
 
virtual void aggregateMassMatrix (Eigen::MatrixXd &_MCol, std::size_t _col)
 
virtual void aggregateAugMassMatrix (Eigen::MatrixXd &_MCol, std::size_t _col, double _timeStep)
 
virtual void updateInvMassMatrix ()
 
virtual void updateInvAugMassMatrix ()
 
virtual void aggregateInvMassMatrix (Eigen::MatrixXd &_InvMCol, std::size_t _col)
 
virtual void aggregateInvAugMassMatrix (Eigen::MatrixXd &_InvMCol, std::size_t _col, double _timeStep)
 
virtual void aggregateCoriolisForceVector (Eigen::VectorXd &_C)
 
virtual void aggregateGravityForceVector (Eigen::VectorXd &_g, const Eigen::Vector3d &_gravity)
 
virtual void updateCombinedVector ()
 
virtual void aggregateCombinedVector (Eigen::VectorXd &_Cg, const Eigen::Vector3d &_gravity)
 
virtual void aggregateExternalForces (Eigen::VectorXd &_Fext)
 Aggregate the external forces mFext in the generalized coordinates recursively. More...
 
virtual void aggregateSpatialToGeneralized (Eigen::VectorXd &_generalized, const Eigen::Vector6d &_spatial)
 
void updateBodyJacobian () const
 Update body Jacobian. More...
 
void updateWorldJacobian () const
 Update the World Jacobian. More...
 
void updateBodyJacobianSpatialDeriv () const
 Update spatial time derivative of body Jacobian. More...
 
void updateWorldJacobianClassicDeriv () const
 Update classic time derivative of body Jacobian. More...
 

Protected Attributes

int mID
 A unique ID of this node globally. More...
 
bool mIsColliding
 Whether the node is currently in collision with another node. More...
 
std::size_t mIndexInSkeleton
 Index of this BodyNode in its Skeleton. More...
 
std::size_t mIndexInTree
 Index of this BodyNode in its Tree. More...
 
std::size_t mTreeIndex
 Index of this BodyNode's tree. More...
 
JointmParentJoint
 Parent joint. More...
 
BodyNodemParentBodyNode
 Parent body node. More...
 
std::vector< BodyNode * > mChildBodyNodes
 Array of child body nodes. More...
 
std::set< Entity * > mNonBodyNodeEntities
 Array of child Entities that are not BodyNodes. More...
 
std::vector< std::size_t > mDependentGenCoordIndices
 A increasingly sorted list of dependent dof indices. More...
 
std::vector< DegreeOfFreedom * > mDependentDofs
 A version of mDependentGenCoordIndices that holds DegreeOfFreedom pointers instead of indices. More...
 
std::vector< const DegreeOfFreedom * > mConstDependentDofs
 Same as mDependentDofs, but holds const pointers. More...
 
math::Jacobian mBodyJacobian
 Body Jacobian. More...
 
math::Jacobian mWorldJacobian
 Cached World Jacobian. More...
 
math::Jacobian mBodyJacobianSpatialDeriv
 Spatial time derivative of body Jacobian. More...
 
math::Jacobian mWorldJacobianClassicDeriv
 Classic time derivative of Body Jacobian. More...
 
Eigen::Vector6d mPartialAcceleration
 Partial spatial body acceleration due to parent joint's velocity. More...
 
bool mIsPartialAccelerationDirty
 Is the partial acceleration vector dirty. More...
 
Eigen::Vector6d mF
 Transmitted wrench from parent to the bodynode expressed in body-fixed frame. More...
 
Eigen::Vector6d mFgravity
 Spatial gravity force. More...
 
math::Inertia mArtInertia
 Articulated body inertia. More...
 
math::Inertia mArtInertiaImplicit
 Articulated body inertia for implicit joint damping and spring forces. More...
 
Eigen::Vector6d mBiasForce
 Bias force. More...
 
Eigen::Vector6d mCg_dV
 Cache data for combined vector of the system. More...
 
Eigen::Vector6d mCg_F
 
Eigen::Vector6d mG_F
 Cache data for gravity force vector of the system. More...
 
Eigen::Vector6d mFext_F
 Cache data for external force vector of the system. More...
 
Eigen::Vector6d mM_dV
 Cache data for mass matrix of the system. More...
 
Eigen::Vector6d mM_F
 
Eigen::Vector6d mInvM_c
 Cache data for inverse mass matrix of the system. More...
 
Eigen::Vector6d mInvM_U
 
Eigen::Vector6d mArbitrarySpatial
 Cache data for arbitrary spatial value. More...
 
Eigen::Vector6d mDelV
 Velocity change due to to external impulsive force exerted on bodies of the parent skeleton. More...
 
Eigen::Vector6d mBiasImpulse
 Impulsive bias force due to external impulsive force exerted on bodies of the parent skeleton. More...
 
Eigen::Vector6d mConstraintImpulse
 Constraint impulse: contact impulse, dynamic joint impulse. More...
 
Eigen::Vector6d mImpF
 Generalized impulsive body force w.r.t. body frame. More...
 
ColShapeAddedSignal mColShapeAddedSignal
 Collision shape added signal. More...
 
ColShapeRemovedSignal mColShapeRemovedSignal
 Collision shape removed signal. More...
 
StructuralChangeSignal mStructuralChangeSignal
 Structural change signal. More...
 
AspectState mAspectState
 Aspect::State data, directly accessible to your derived class. More...
 
AspectProperties mAspectProperties
 Aspect::Properties data, directly accessible to your derived class. More...
 
std::weak_ptr< SkeletonmSkeleton
 Weak pointer to the Skeleton this BodyNode belongs to. More...
 
std::atomic< int > mReferenceCount
 Reference count for the number of BodyNodePtrs that are referring to this BodyNode. More...
 
std::shared_ptr< SkeletonmReferenceSkeleton
 If mReferenceCount is zero, then mReferenceSkeleton will hold a nullptr. More...
 
std::shared_ptr< MutexedWeakSkeletonPtrmLockedSkeleton
 Shared reference to a weak_ptr of this BodyNode's Skeleton, along with a mutex to ensure thread safety. More...
 
bool mIsBodyJacobianDirty
 Dirty flag for body Jacobian. More...
 
bool mIsWorldJacobianDirty
 Dirty flag for world Jacobian. More...
 
bool mIsBodyJacobianSpatialDerivDirty
 Dirty flag for spatial time derivative of body Jacobian. More...
 
bool mIsWorldJacobianClassicDerivDirty
 Dirty flag for the classic time derivative of the Jacobian. More...
 
std::shared_ptr< InverseKinematicsmIK
 Inverse kinematics module which gets lazily created upon request. More...
 
std::unordered_set< JacobianNode * > mChildJacobianNodes
 JacobianNode children that descend from this JacobianNode. More...
 
Eigen::Isometry3d mWorldTransform
 World transform of this Frame. More...
 
Eigen::Vector6d mVelocity
 Total velocity of this Frame, in the coordinates of this Frame. More...
 
Eigen::Vector6d mAcceleration
 Total acceleration of this Frame, in the coordinates of this Frame. More...
 
std::set< Frame * > mChildFrames
 Container of this Frame's child Frames. More...
 
std::set< Entity * > mChildEntities
 Container of this Frame's child Entities. More...
 
FramemParentFrame
 Parent frame of this Entity. More...
 
bool mNeedTransformUpdate
 Does this Entity need a Transform update. More...
 
bool mNeedVelocityUpdate
 Does this Entity need a Velocity update. More...
 
bool mNeedAccelerationUpdate
 Does this Entity need an Acceleration update. More...
 
FrameChangedSignal mFrameChangedSignal
 Frame changed signal. More...
 
NameChangedSignal mNameChangedSignal
 Name changed signal. More...
 
EntitySignal mTransformUpdatedSignal
 Transform changed signal. More...
 
EntitySignal mVelocityChangedSignal
 Velocity changed signal. More...
 
EntitySignal mAccelerationChangedSignal
 Acceleration changed signal. More...
 
std::set< Observer * > mObservers
 List of current Observers. More...
 
std::weak_ptr< NodeDestructormDestructor
 weak pointer to the destructor for this Node. More...
 
BodyNodemBodyNode
 Pointer to the BodyNode that this Node is attached to. More...
 
bool mAmAttached
 bool that tracks whether this Node is attached to its BodyNode More...
 
std::size_t mIndexInBodyNode
 The index of this Node within its vector in its BodyNode's NodeMap. More...
 
std::size_t mVersion
 

Static Protected Attributes

static std::size_t msBodyNodeCount = 0
 Counts the number of nodes globally. More...
 

Private Types

enum  ConstructWorldTag { ConstructWorld }
 Used when constructing the World. More...
 

Private Member Functions

void incrementReferenceCount () const
 Atomically increment the reference count for this BodyNode. More...
 
void decrementReferenceCount () const
 Atomically decrement the reference count for this BodyNode. More...
 
std::shared_ptr< NodeDestructorgetOrCreateDestructor ()
 

Private Attributes

std::shared_ptr< NodeDestructormSelfDestructor
 Hold onto a reference to this BodyNode's own Destructor to make sure that it never gets destroyed. More...
 
const bool mAmWorld
 Contains whether or not this is the World Frame. More...
 
bool mAmShapeFrame
 Contains whether or not this is a ShapeFrame. More...
 
VersionCountermDependent
 

Friends

class Skeleton
 
class Joint
 
class EndEffector
 
class SoftBodyNode
 
class PointMass
 
class Node
 

Slot registers

common::SlotRegister< FrameChangedSignalonFrameChanged
 Slot register for frame changed signal. More...
 
common::SlotRegister< NameChangedSignalonNameChanged
 Slot register for name changed signal. More...
 
common::SlotRegister< EntitySignalonTransformUpdated
 Slot register for transform updated signal. More...
 
common::SlotRegister< EntitySignalonVelocityChanged
 Slot register for velocity updated signal. More...
 
common::SlotRegister< EntitySignalonAccelerationChanged
 Slot register for acceleration updated signal. More...
 
const bool mAmQuiet
 Whether or not this Entity is set to be quiet. More...
 
bool mAmFrame
 Whether or not this Entity is a Frame. More...
 

Detailed Description

BodyNode class represents a single node of the skeleton.

BodyNode is a basic element of the skeleton. BodyNodes are hierarchically connected and have a set of core functions for calculating derivatives.

BodyNode inherits Frame, and a parent Frame of a BodyNode is the parent BodyNode of the BodyNode.

Member Typedef Documentation

◆ AllNodeProperties

◆ AllNodeStates

◆ Aspect

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::Aspect = typename Impl::Aspect
inherited

◆ AspectProperties

◆ AspectPropertiesData

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::AspectPropertiesData = typename Impl::AspectPropertiesData
inherited

◆ AspectState

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::AspectState = typename Impl::AspectState
inherited

◆ AspectStateData

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::AspectStateData = typename Impl::AspectStateData
inherited

◆ Base

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::Base = CompositeJoiner<Impl, CompositeBases...>
inherited

◆ ColShapeAddedSignal

◆ ColShapeRemovedSignal

◆ CompositeProperties

◆ Derived

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::Derived = typename Impl::Derived
inherited

◆ EntitySignal

◆ FrameChangedSignal

using dart::dynamics::Entity::FrameChangedSignal = common::Signal<void(const Entity*, const Frame* _oldFrame, const Frame* _newFrame)>
inherited

◆ Impl

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
using dart::common::EmbedStateAndPropertiesOnTopOf< DerivedT, StateDataT, PropertiesDataT, CompositeBases >::Impl = EmbedStateAndProperties<DerivedT, StateDataT, PropertiesDataT>
inherited

◆ MakeProperties

template<class Mixin >
using dart::dynamics::Node::MakeProperties = common::MakeCloneable<Properties, Mixin>
inherited

Use the MakeProperties class to easily create a Properties extension from an existing class or struct.

◆ MakeState

template<class Mixin >
using dart::dynamics::Node::MakeState = common::MakeCloneable<State, Mixin>
inherited

Use the MakeState class to easily create a State extension from an existing class or struct.

◆ NameChangedSignal

using dart::dynamics::Entity::NameChangedSignal = common::Signal<void(const Entity*, const std::string& _oldName, const std::string& _newName)>
inherited

◆ NodePropertiesMap

◆ NodeStateMap

◆ Properties

◆ StructuralChangeSignal

Member Enumeration Documentation

◆ ConstructAbstractTag

Used when constructing a pure abstract class, because calling the Frame constructor is just a formality.

Enumerator
ConstructAbstract 

◆ ConstructFrameTag

Used when constructing a Frame class, because the Frame constructor will take care of setting up the parameters you pass into it.

Enumerator
ConstructFrame 

◆ ConstructWorldTag

Used when constructing the World.

Enumerator
ConstructWorld 

Constructor & Destructor Documentation

◆ BodyNode() [1/3]

dart::dynamics::BodyNode::BodyNode ( const BodyNode )
delete

◆ ~BodyNode()

dart::dynamics::BodyNode::~BodyNode ( )
virtual

Destructor.

◆ BodyNode() [2/3]

dart::dynamics::BodyNode::BodyNode ( BodyNode _parentBodyNode,
Joint _parentJoint,
const Properties _properties 
)
protected

Constructor called by Skeleton class.

◆ BodyNode() [3/3]

dart::dynamics::BodyNode::BodyNode ( const std::tuple< BodyNode *, Joint *, Properties > &  args)
protected

Delegating constructor.

Member Function Documentation

◆ addChildBodyNode()

void dart::dynamics::BodyNode::addChildBodyNode ( BodyNode _body)
protected

Add a child bodynode into the bodynode.

◆ addConstraintImpulse() [1/2]

void dart::dynamics::BodyNode::addConstraintImpulse ( const Eigen::Vector3d &  _constImp,
const Eigen::Vector3d &  _offset,
bool  _isImpulseLocal = false,
bool  _isOffsetLocal = true 
)

Add constraint impulse.

◆ addConstraintImpulse() [2/2]

void dart::dynamics::BodyNode::addConstraintImpulse ( const Eigen::Vector6d _constImp)

Add constraint impulse.

Parameters
[in]_constImpSpatial constraint impulse w.r.t. body frame

◆ addExtForce()

void dart::dynamics::BodyNode::addExtForce ( const Eigen::Vector3d &  _force,
const Eigen::Vector3d &  _offset = Eigen::Vector3d::Zero(),
bool  _isForceLocal = false,
bool  _isOffsetLocal = true 
)

Add applying linear Cartesian forces to this node.

A force is defined by a point of application and a force vector. The last two parameters specify frames of the first two parameters. Coordinate transformations are applied when needed. The point of application and the force in local coordinates are stored in mContacts. When conversion is needed, make sure the transformations are avaialble.

◆ addExtTorque()

void dart::dynamics::BodyNode::addExtTorque ( const Eigen::Vector3d &  _torque,
bool  _isLocal = false 
)

Add applying Cartesian torque to the node.

The torque in local coordinates is accumulated in mExtTorqueBody.

◆ addObserver()

void dart::common::Subject::addObserver ( Observer _observer) const
protectedinherited

Add an Observer to the list of Observers.

◆ aggregateAugMassMatrix()

void dart::dynamics::BodyNode::aggregateAugMassMatrix ( Eigen::MatrixXd &  _MCol,
std::size_t  _col,
double  _timeStep 
)
protectedvirtual

◆ aggregateCombinedVector()

void dart::dynamics::BodyNode::aggregateCombinedVector ( Eigen::VectorXd &  _Cg,
const Eigen::Vector3d &  _gravity 
)
protectedvirtual

◆ aggregateCoriolisForceVector()

void dart::dynamics::BodyNode::aggregateCoriolisForceVector ( Eigen::VectorXd &  _C)
protectedvirtual

◆ aggregateExternalForces()

void dart::dynamics::BodyNode::aggregateExternalForces ( Eigen::VectorXd &  _Fext)
protectedvirtual

Aggregate the external forces mFext in the generalized coordinates recursively.

◆ aggregateGravityForceVector()

void dart::dynamics::BodyNode::aggregateGravityForceVector ( Eigen::VectorXd &  _g,
const Eigen::Vector3d &  _gravity 
)
protectedvirtual

◆ aggregateInvAugMassMatrix()

void dart::dynamics::BodyNode::aggregateInvAugMassMatrix ( Eigen::MatrixXd &  _InvMCol,
std::size_t  _col,
double  _timeStep 
)
protectedvirtual

◆ aggregateInvMassMatrix()

void dart::dynamics::BodyNode::aggregateInvMassMatrix ( Eigen::MatrixXd &  _InvMCol,
std::size_t  _col 
)
protectedvirtual

◆ aggregateMassMatrix()

void dart::dynamics::BodyNode::aggregateMassMatrix ( Eigen::MatrixXd &  _MCol,
std::size_t  _col 
)
protectedvirtual

◆ aggregateSpatialToGeneralized()

void dart::dynamics::BodyNode::aggregateSpatialToGeneralized ( Eigen::VectorXd &  _generalized,
const Eigen::Vector6d _spatial 
)
protectedvirtual

◆ asShapeFrame() [1/2]

ShapeFrame * dart::dynamics::Frame::asShapeFrame ( )
virtualinherited

Convert 'this' into a ShapeFrame pointer if Frame is a ShapeFrame, otherwise return nullptr.

Reimplemented in dart::dynamics::ShapeFrame.

◆ asShapeFrame() [2/2]

const ShapeFrame * dart::dynamics::Frame::asShapeFrame ( ) const
virtualinherited

Convert 'const this' into a ShapeFrame pointer if Frame is a ShapeFrame, otherwise return nullptr.

Reimplemented in dart::dynamics::ShapeFrame.

◆ asSoftBodyNode() [1/2]

SoftBodyNode * dart::dynamics::BodyNode::asSoftBodyNode ( )
virtual

Convert 'this' into a SoftBodyNode pointer if this BodyNode is a SoftBodyNode, otherwise return nullptr.

◆ asSoftBodyNode() [2/2]

const SoftBodyNode * dart::dynamics::BodyNode::asSoftBodyNode ( ) const
virtual

Convert 'const this' into a SoftBodyNode pointer if this BodyNode is a SoftBodyNode, otherwise return nullptr.

◆ attach()

void dart::dynamics::Node::attach ( )
protectedinherited

Attach the Node to its BodyNode.

◆ changeParentFrame()

void dart::dynamics::Frame::changeParentFrame ( Frame _newParentFrame)
overrideprotectedvirtualinherited

Used by derived classes to change their parent frames.

Reimplemented from dart::dynamics::Entity.

◆ changeParentJointType()

template<class JointType >
JointType * dart::dynamics::BodyNode::changeParentJointType ( const typename JointType::Properties &  _joint = typename JointType::Properties())

Change the Joint type of this BodyNode's parent Joint.

Note that this function will change the indexing of (potentially) all BodyNodes and Joints in the Skeleton.

◆ clearConstraintImpulse()

void dart::dynamics::BodyNode::clearConstraintImpulse ( )
virtual

Clear constraint impulses and cache data used for impulse-based forward dynamics algorithm.

◆ clearExternalForces()

void dart::dynamics::BodyNode::clearExternalForces ( )
virtual

Clean up structures that store external forces: mContacts, mFext, mExtForceBody and mExtTorqueBody.

Called by Skeleton::clearExternalForces.

◆ clearIK()

void dart::dynamics::JacobianNode::clearIK ( )
inherited

Wipe away the IK module for this JacobianNode, leaving it as a nullptr.

◆ clearInternalForces()

void dart::dynamics::BodyNode::clearInternalForces ( )
virtual

Clear out the generalized forces of the parent Joint and any other forces related to this BodyNode that are internal to the Skeleton.

For example, the point mass forces for SoftBodyNodes.

◆ clone()

BodyNode * dart::dynamics::BodyNode::clone ( BodyNode _parentBodyNode,
Joint _parentJoint,
bool  cloneNodes 
) const
protectedvirtual

Create a clone of this BodyNode.

This may only be called by the Skeleton class.

◆ cloneNode()

Node * dart::dynamics::BodyNode::cloneNode ( BodyNode bn) const
finaloverrideprotectedvirtual

This is needed in order to inherit the Node class, but it does nothing.

Implements dart::dynamics::Node.

◆ computeKineticEnergy()

double dart::dynamics::BodyNode::computeKineticEnergy ( ) const

Return kinetic energy.

◆ computeLagrangian()

double dart::dynamics::BodyNode::computeLagrangian ( const Eigen::Vector3d &  gravity) const

Return Lagrangian of this body.

◆ computePotentialEnergy()

double dart::dynamics::BodyNode::computePotentialEnergy ( const Eigen::Vector3d &  gravity) const

Return potential energy.

◆ copy() [1/2]

void dart::dynamics::BodyNode::copy ( const BodyNode otherBodyNode)

Copy the Properties of another BodyNode.

◆ copy() [2/2]

void dart::dynamics::BodyNode::copy ( const BodyNode otherBodyNode)

Copy the Properties of another BodyNode.

◆ copyAs() [1/2]

SkeletonPtr dart::dynamics::BodyNode::copyAs ( const std::string &  _skeletonName,
bool  _recursive = true 
) const

Create clones of this BodyNode and all of its children (recursively) and create a new Skeleton with the specified name to attach them to.

The Skeleton::Properties of the current Skeleton will also be copied into the new Skeleton that gets created.

◆ copyAs() [2/2]

template<class JointType >
SkeletonPtr dart::dynamics::BodyNode::copyAs ( const std::string &  _skeletonName,
const typename JointType::Properties &  _joint = typename JointType::Properties(),
bool  _recursive = true 
) const

A version of copyAs(const std::string&) that also changes the Joint type of the root BodyNode.

◆ copyNodePropertiesTo()

void dart::dynamics::Node::copyNodePropertiesTo ( std::unique_ptr< Properties > &  outputProperties) const
virtualinherited

Copy the Properties of this Node into a unique_ptr.

By default, this simply calls getNodeProperties() and passes the result into the outputProperties, but this function can be overriden to be more performant.

◆ copyNodeStateTo()

void dart::dynamics::Node::copyNodeStateTo ( std::unique_ptr< State > &  outputState) const
virtualinherited

Copy the State of this Node into a unique_ptr.

By default, this simply calls getNodeState() and passes the result into the outputState, but this function can be overriden to be more performant by avoiding allocations.

◆ copyTo() [1/4]

std::pair< Joint *, BodyNode * > dart::dynamics::BodyNode::copyTo ( BodyNode _newParent,
bool  _recursive = true 
)

Create clones of this BodyNode and all of its children recursively (unless _recursive is set to false) and attach the clones to the specified BodyNode.

The specified BodyNode can be in this Skeleton or a different Skeleton. Passing in nullptr will set the copy as a root node of the current Skeleton.

The return value is a pair of pointers to the root of the newly created BodyNode tree.

◆ copyTo() [2/4]

template<class JointType >
std::pair< JointType *, BodyNode * > dart::dynamics::BodyNode::copyTo ( BodyNode _newParent,
const typename JointType::Properties &  _joint = typename JointType::Properties(),
bool  _recursive = true 
)

A version of copyTo(BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode.

◆ copyTo() [3/4]

std::pair< Joint *, BodyNode * > dart::dynamics::BodyNode::copyTo ( const SkeletonPtr _newSkeleton,
BodyNode _newParent,
bool  _recursive = true 
) const

Create clones of this BodyNode and all of its children recursively (unless recursive is set to false) and attach the clones to the specified BodyNode of the specified Skeleton.

The key differences between this function and the copyTo(BodyNode*) version is that this one allows the copied BodyNode to be const and allows you to copy it as a root node of another Skeleton.

The return value is a pair of pointers to the root of the newly created BodyNode tree.

◆ copyTo() [4/4]

template<class JointType >
std::pair< JointType *, BodyNode * > dart::dynamics::BodyNode::copyTo ( const SkeletonPtr _newSkeleton,
BodyNode _newParent,
const typename JointType::Properties &  _joint = typename JointType::Properties(),
bool  _recursive = true 
) const

A version of copyTo(Skeleton*,BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode.

◆ createChildJointAndBodyNodePair()

template<class JointType , class NodeType >
std::pair< JointType *, NodeType * > dart::dynamics::BodyNode::createChildJointAndBodyNodePair ( const typename JointType::Properties &  _jointProperties = typename JointType::Properties(),
const typename NodeType::Properties &  _bodyProperties = typename NodeType::Properties() 
)

Create a Joint and BodyNode pair as a child of this BodyNode.

◆ createEndEffector() [1/3]

EndEffector * dart::dynamics::BodyNode::createEndEffector ( const char *  _name)

Create an EndEffector with the specified name.

◆ createEndEffector() [2/3]

EndEffector * dart::dynamics::BodyNode::createEndEffector ( const EndEffector::BasicProperties _properties)

Create an EndEffector attached to this BodyNode.

Pass an EndEffector::Properties argument into this function.

◆ createEndEffector() [3/3]

EndEffector * dart::dynamics::BodyNode::createEndEffector ( const std::string &  _name = "EndEffector")

Create an EndEffector with the specified name.

◆ createIK()

const std::shared_ptr< InverseKinematics > & dart::dynamics::JacobianNode::createIK ( )
inherited

Create a new IK module for this JacobianNode.

If an IK module already exists in this JacobianNode, it will be destroyed and replaced by a brand new one.

◆ createMarker() [1/2]

Marker * dart::dynamics::BodyNode::createMarker ( const Marker::BasicProperties properties)

Create a Marker given its basic properties.

◆ createMarker() [2/2]

Marker * dart::dynamics::BodyNode::createMarker ( const std::string &  name = "marker",
const Eigen::Vector3d &  position = Eigen::Vector3d::Zero(),
const Eigen::Vector4d &  color = Eigen::Vector4d::Constant(1.0) 
)

Create a Marker with the given fields.

◆ createNode()

template<class NodeType , typename ... Args>
NodeType * dart::dynamics::BodyNode::createNode ( Args &&...  args)

Create some Node type and attach it to this BodyNode.

◆ createShapeNode() [1/3]

template<class ShapeType >
ShapeNode * dart::dynamics::BodyNode::createShapeNode ( const std::shared_ptr< ShapeType > &  shape)

Create a ShapeNode with an automatically assigned name: <BodyNodeName>ShapeNode<#>.

◆ createShapeNode() [2/3]

template<class ShapeType , class StringType >
ShapeNode * dart::dynamics::BodyNode::createShapeNode ( const std::shared_ptr< ShapeType > &  shape,
StringType &&  name 
)

Create a ShapeNode with the specified name.

◆ createShapeNode() [3/3]

template<class ShapeNodeProperties >
ShapeNode * dart::dynamics::BodyNode::createShapeNode ( ShapeNodeProperties  properties,
bool  automaticName = true 
)

Create an ShapeNode attached to this BodyNode.

Pass a ShapeNode::Properties argument into its constructor. If automaticName is true, then the mName field of properties will be ignored, and the ShapeNode will be automatically assigned a name: <BodyNodeName>ShapeNode<#>

◆ createShapeNodeWith() [1/2]

template<class... Aspects>
ShapeNode * dart::dynamics::BodyNode::createShapeNodeWith ( const ShapePtr shape)

Create a ShapeNode with the specified Aspects and an automatically assigned name: <BodyNodeName>ShapeNode<#>.

◆ createShapeNodeWith() [2/2]

template<class... Aspects>
ShapeNode * dart::dynamics::BodyNode::createShapeNodeWith ( const ShapePtr shape,
const std::string &  name 
)

Create a ShapeNode with the specified name and Aspects.

◆ decrementReferenceCount()

void dart::dynamics::SkeletonRefCountingBase::decrementReferenceCount ( ) const
privateinherited

Atomically decrement the reference count for this BodyNode.

This should only be called by the BodyNodePtr class

◆ dependsOn()

bool dart::dynamics::BodyNode::dependsOn ( std::size_t  _genCoordIndex) const
overridevirtual

Return true if _genCoordIndex-th generalized coordinate.

Implements dart::dynamics::JacobianNode.

◆ descendsFrom()

bool dart::dynamics::Entity::descendsFrom ( const Frame _someFrame) const
inherited

True if and only if this Entity depends on (i.e.

kinematically descends from) _someFrame. If _someFrame is nullptr, this returns true in order to accommodate BodyNodes which always have a nullptr BodyNode as the parent of a root BodyNode.

◆ dirtyAcceleration()

void dart::dynamics::BodyNode::dirtyAcceleration ( )
overridevirtual

Notify the acceleration updates of this Frame and all its children are needed.

Reimplemented from dart::dynamics::Frame.

◆ dirtyArticulatedInertia()

void dart::dynamics::BodyNode::dirtyArticulatedInertia ( )

Notify the Skeleton that the tree of this BodyNode needs an articulated inertia update.

◆ dirtyCoriolisForces()

void dart::dynamics::BodyNode::dirtyCoriolisForces ( )

Tell the Skeleton that the coriolis forces need to be update.

◆ dirtyExternalForces()

void dart::dynamics::BodyNode::dirtyExternalForces ( )

Tell the Skeleton that the external forces need to be updated.

◆ dirtyJacobian()

void dart::dynamics::JacobianNode::dirtyJacobian ( )
inherited

Notify this BodyNode and all its descendents that their Jacobians need to be updated.

◆ dirtyJacobianDeriv()

void dart::dynamics::JacobianNode::dirtyJacobianDeriv ( )
inherited

Notify this BodyNode and all its descendents that their Jacobian derivatives need to be updated.

◆ dirtyTransform()

void dart::dynamics::BodyNode::dirtyTransform ( )
overridevirtual

Notify the transformation updates of this Frame and all its children are needed.

Reimplemented from dart::dynamics::Frame.

◆ dirtyVelocity()

void dart::dynamics::BodyNode::dirtyVelocity ( )
overridevirtual

Notify the velocity updates of this Frame and all its children are needed.

Reimplemented from dart::dynamics::Frame.

◆ duplicateNodes()

void dart::dynamics::BodyNode::duplicateNodes ( const BodyNode otherBodyNode)

Give this BodyNode a copy of each Node from otherBodyNode.

◆ getAllNodeProperties()

BodyNode::AllNodeProperties dart::dynamics::BodyNode::getAllNodeProperties ( ) const

Get the Node::Properties of all Nodes attached to this BodyNode.

◆ getAllNodeStates()

BodyNode::AllNodeStates dart::dynamics::BodyNode::getAllNodeStates ( ) const

Get the Node::State of all Nodes attached to this BodyNode.

◆ getAngularAcceleration()

Eigen::Vector3d dart::dynamics::Frame::getAngularAcceleration ( const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const
inherited

Get the angular portion of classical acceleration of this Frame relative to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getAngularJacobian()

math::AngularJacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getAngularJacobian ( const Frame _inCoordinatesOf = Frame::World()) const
finaloverridevirtualinherited

Return the angular Jacobian targeting the origin of this BodyNode.

You can specify a coordinate Frame to express the Jacobian in.

Implements dart::dynamics::JacobianNode.

◆ getAngularJacobianDeriv()

math::AngularJacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getAngularJacobianDeriv ( const Frame _inCoordinatesOf = Frame::World()) const
finaloverridevirtualinherited

Return the angular Jacobian time derivative, in terms of any coordinate Frame.

Implements dart::dynamics::JacobianNode.

◆ getAngularMomentum()

Eigen::Vector3d dart::dynamics::BodyNode::getAngularMomentum ( const Eigen::Vector3d &  _pivot = Eigen::Vector3d::Zero())

Return angular momentum.

◆ getAngularVelocity()

Eigen::Vector3d dart::dynamics::Frame::getAngularVelocity ( const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const
inherited

Get the angular portion of classical velocity of this Frame relative to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getArticulatedInertia()

const math::Inertia & dart::dynamics::BodyNode::getArticulatedInertia ( ) const

Return the articulated body inertia.

◆ getArticulatedInertiaImplicit()

const math::Inertia & dart::dynamics::BodyNode::getArticulatedInertiaImplicit ( ) const

Return the articulated body inertia for implicit joint damping and spring forces.

◆ getAspectProperties()

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
const AspectProperties& dart::common::EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT >::getAspectProperties
inlineinherited

◆ getAspectState()

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
const AspectState& dart::common::EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT >::getAspectState
inlineinherited

◆ getBodyForce()

const Eigen::Vector6d & dart::dynamics::BodyNode::getBodyForce ( ) const

Get spatial body force transmitted from the parent joint.

The spatial body force is transmitted to this BodyNode from the parent body through the connecting joint. It is expressed in this BodyNode's frame.

◆ getBodyNodeProperties()

BodyNode::Properties dart::dynamics::BodyNode::getBodyNodeProperties ( ) const

Get the Properties of this BodyNode.

◆ getBodyNodePtr() [1/2]

BodyNodePtr dart::dynamics::Node::getBodyNodePtr ( )
inherited

Get a pointer to the BodyNode that this Node is associated with.

◆ getBodyNodePtr() [2/2]

ConstBodyNodePtr dart::dynamics::Node::getBodyNodePtr ( ) const
inherited

Get a pointer to the BodyNode that this Node is associated with.

◆ getBodyVelocityChange()

const Eigen::Vector6d & dart::dynamics::BodyNode::getBodyVelocityChange ( ) const

Return the velocity change due to the constraint impulse.

◆ getChainDofs()

const std::vector< const DegreeOfFreedom * > dart::dynamics::BodyNode::getChainDofs ( ) const
overridevirtual

Returns a DegreeOfFreedom vector containing the dofs that form a Chain leading up to this JacobianNode from the root of the Skeleton.

Implements dart::dynamics::JacobianNode.

◆ getChildBodyNode() [1/2]

BodyNode * dart::dynamics::BodyNode::getChildBodyNode ( std::size_t  _index)

Return the _index-th child BodyNode of this BodyNode.

◆ getChildBodyNode() [2/2]

const BodyNode * dart::dynamics::BodyNode::getChildBodyNode ( std::size_t  _index) const

Return the (const) _index-th child BodyNode of this BodyNode.

◆ getChildEntities() [1/2]

const std::set< Entity * > & dart::dynamics::Frame::getChildEntities ( )
inherited

Get a container with the Entities that are children of this Frame.

std::set is used because Entities may be arbitrarily added and removed from a parent Frame, and each entry should be unique. std::set makes this procedure easier.

◆ getChildEntities() [2/2]

const std::set< const Entity * > dart::dynamics::Frame::getChildEntities ( ) const
inherited

Get a container with the Entities that are children of this Frame.

Note that this is version is slightly less efficient than the non-const version because it needs to rebuild a set where each pointer is converted to be a const pointer.

◆ getChildFrames() [1/2]

const std::set< Frame * > & dart::dynamics::Frame::getChildFrames ( )
inherited

Get a container with the Frames that are children of this Frame.

std::set is used because Frames may be arbitrarily added and removed from a parent Frame, and each entry should be unique.

◆ getChildFrames() [2/2]

std::set< const Frame * > dart::dynamics::Frame::getChildFrames ( ) const
inherited

Get a container with the Frames that are children of this Frame.

Note that this version is less efficient than the non-const version because it needs to rebuild a set so that the entries are const.

◆ getChildJoint() [1/2]

Joint * dart::dynamics::BodyNode::getChildJoint ( std::size_t  _index)

Return the _index-th child Joint of this BodyNode.

◆ getChildJoint() [2/2]

const Joint * dart::dynamics::BodyNode::getChildJoint ( std::size_t  _index) const

Return the (const) _index-th child Joint of this BodyNode.

◆ getCOM()

Eigen::Vector3d dart::dynamics::BodyNode::getCOM ( const Frame _withRespectTo = Frame::World()) const

Return the center of mass with respect to an arbitrary Frame.

◆ getCOMLinearAcceleration()

Eigen::Vector3d dart::dynamics::BodyNode::getCOMLinearAcceleration ( const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const

Return the linear acceleration of the center of mass, expressed in terms of arbitary Frames.

◆ getCOMLinearVelocity()

Eigen::Vector3d dart::dynamics::BodyNode::getCOMLinearVelocity ( const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const

Return the linear velocity of the center of mass, expressed in terms of arbitrary Frames.

◆ getCOMSpatialAcceleration() [1/2]

Eigen::Vector6d dart::dynamics::BodyNode::getCOMSpatialAcceleration ( ) const

Return the acceleration of the center of mass expressed in coordinates of this BodyNode Frame and relative to the World Frame.

◆ getCOMSpatialAcceleration() [2/2]

Eigen::Vector6d dart::dynamics::BodyNode::getCOMSpatialAcceleration ( const Frame _relativeTo,
const Frame _inCoordinatesOf 
) const

Return the spatial acceleration of the center of mass, expressed in terms of arbitrary Frames.

◆ getCOMSpatialVelocity() [1/2]

Eigen::Vector6d dart::dynamics::BodyNode::getCOMSpatialVelocity ( ) const

Return the spatial velocity of the center of mass, expressed in coordinates of this Frame and relative to the World Frame.

◆ getCOMSpatialVelocity() [2/2]

Eigen::Vector6d dart::dynamics::BodyNode::getCOMSpatialVelocity ( const Frame _relativeTo,
const Frame _inCoordinatesOf 
) const

Return the spatial velocity of the center of mass, expressed in terms of arbitrary Frames.

◆ getConstraintImpulse()

const Eigen::Vector6d & dart::dynamics::BodyNode::getConstraintImpulse ( ) const

Return constraint impulse.

◆ getDependentDof() [1/2]

const DegreeOfFreedom * dart::dynamics::BodyNode::getDependentDof ( std::size_t  _index) const
overridevirtual

Get a pointer to the _indexth dependent DegreeOfFreedom for this BodyNode.

Implements dart::dynamics::JacobianNode.

◆ getDependentDof() [2/2]

DegreeOfFreedom * dart::dynamics::BodyNode::getDependentDof ( std::size_t  _index)
overridevirtual

Get a pointer to the _indexth dependent DegreeOfFreedom for this BodyNode.

Implements dart::dynamics::JacobianNode.

◆ getDependentDofs() [1/2]

const std::vector< const DegreeOfFreedom * > & dart::dynamics::BodyNode::getDependentDofs ( ) const
overridevirtual

Return a std::vector of DegreeOfFreedom pointers that this Node depends on.

Implements dart::dynamics::JacobianNode.

◆ getDependentDofs() [2/2]

const std::vector< DegreeOfFreedom * > & dart::dynamics::BodyNode::getDependentDofs ( )
overridevirtual

Return a std::vector of DegreeOfFreedom pointers that this Node depends on.

Implements dart::dynamics::JacobianNode.

◆ getDependentGenCoordIndex()

std::size_t dart::dynamics::BodyNode::getDependentGenCoordIndex ( std::size_t  _arrayIndex) const
overridevirtual

Return a generalized coordinate index from the array index (< getNumDependentDofs)

Implements dart::dynamics::JacobianNode.

◆ getDependentGenCoordIndices()

const std::vector< std::size_t > & dart::dynamics::BodyNode::getDependentGenCoordIndices ( ) const
overridevirtual

Indices of the generalized coordinates which affect this JacobianNode.

Implements dart::dynamics::JacobianNode.

◆ getEndEffector() [1/2]

EndEffector * dart::dynamics::BodyNode::getEndEffector ( std::size_t  index)

◆ getEndEffector() [2/2]

const EndEffector * dart::dynamics::BodyNode::getEndEffector ( std::size_t  index) const

◆ getExternalForceGlobal()

Eigen::Vector6d dart::dynamics::BodyNode::getExternalForceGlobal ( ) const

◆ getExternalForceLocal()

const Eigen::Vector6d & dart::dynamics::BodyNode::getExternalForceLocal ( ) const

◆ getFrictionCoeff()

double dart::dynamics::BodyNode::getFrictionCoeff ( ) const

Return frictional coefficient.

◆ getGravityMode()

bool dart::dynamics::BodyNode::getGravityMode ( ) const

Return true if gravity mode is enabled.

◆ getIK() [1/2]

std::shared_ptr< const InverseKinematics > dart::dynamics::JacobianNode::getIK ( ) const
inherited

Get a pointer to an IK module for this JacobianNode.

Because this is a const function, a new IK module cannot be created if one does not already exist.

◆ getIK() [2/2]

const std::shared_ptr< InverseKinematics > & dart::dynamics::JacobianNode::getIK ( bool  _createIfNull = false)
inherited

Get a pointer to an IK module for this JacobianNode.

If _createIfNull is true, then the IK module will be generated if one does not already exist.

◆ getIndexInSkeleton()

std::size_t dart::dynamics::BodyNode::getIndexInSkeleton ( ) const

Return the index of this BodyNode within its Skeleton.

◆ getIndexInTree()

std::size_t dart::dynamics::BodyNode::getIndexInTree ( ) const

Return the index of this BodyNode within its tree.

◆ getInertia()

const Inertia & dart::dynamics::BodyNode::getInertia ( ) const

Get the inertia data for this BodyNode.

◆ getJacobian() [1/4]

const math::Jacobian & dart::dynamics::BodyNode::getJacobian ( ) const
finaloverridevirtual

Return the generalized Jacobian targeting the origin of this BodyNode.

The Jacobian is expressed in the Frame of this BodyNode.

Implements dart::dynamics::JacobianNode.

◆ getJacobian() [2/4]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobian ( const Eigen::Vector3d &  _offset) const
finaloverridevirtualinherited

Return the generalized Jacobian targeting an offset within the Frame of this JacobianNode.

Implements dart::dynamics::JacobianNode.

◆ getJacobian() [3/4]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobian ( const Eigen::Vector3d &  _offset,
const Frame _inCoordinatesOf 
) const
finaloverridevirtualinherited

A version of getJacobian(const Eigen::Vector3d&) that lets you specify a coordinate Frame to express the Jacobian in.

Implements dart::dynamics::JacobianNode.

◆ getJacobian() [4/4]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobian ( const Frame _inCoordinatesOf) const
finaloverridevirtualinherited

A version of getJacobian() that lets you specify a coordinate Frame to express the Jacobian in.

Implements dart::dynamics::JacobianNode.

◆ getJacobianClassicDeriv() [1/3]

const math::Jacobian & dart::dynamics::BodyNode::getJacobianClassicDeriv ( ) const
finaloverridevirtual

Return the classical time derivative of the generalized Jacobian targeting the origin of this BodyNode.

The Jacobian is expressed in the World coordinate Frame.

NOTE: Since this is a classical time derivative, it should be used with classical linear and angular vectors. If you are using spatial vectors, use getJacobianSpatialDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getJacobianClassicDeriv() [2/3]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobianClassicDeriv ( const Eigen::Vector3d &  _offset,
const Frame _inCoordinatesOf = Frame::World() 
) const
finaloverridevirtualinherited

A version of getJacobianClassicDeriv() that can compute the Jacobian for an offset within the Frame of this BodyNode.

The offset must be expressed in the coordinates of this BodyNode Frame.

NOTE: Since this is a classical time derivative, it should be used with classical linear and angular vectors. If you are using spatial vectors, use getJacobianSpatialDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getJacobianClassicDeriv() [3/3]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobianClassicDeriv ( const Frame _inCoordinatesOf) const
finaloverridevirtualinherited

A version of getJacobianClassicDeriv() that can return the Jacobian in coordinates of any Frame.

NOTE: Since this is a classical time derivative, it should be used with classical linear and angular vectors. If you are using spatial vectors, use getJacobianSpatialDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getJacobianSpatialDeriv() [1/4]

const math::Jacobian & dart::dynamics::BodyNode::getJacobianSpatialDeriv ( ) const
finaloverridevirtual

Return the spatial time derivative of the generalized Jacobian targeting the origin of this BodyNode.

The Jacobian is expressed in this BodyNode's coordinate Frame.

NOTE: Since this is a spatial time derivative, it should be used with spatial vectors. If you are using classical linear and angular acceleration vectors, then use getJacobianClassicDeriv(), getLinearJacobianDeriv(), or getAngularJacobianDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getJacobianSpatialDeriv() [2/4]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobianSpatialDeriv ( const Eigen::Vector3d &  _offset) const
finaloverridevirtualinherited

Return the spatial time derivative of the generalized Jacobian targeting an offset in the Frame of this BodyNode.

The Jacobian is expressed in this BodyNode's coordinate Frame.

NOTE: This Jacobian Derivative is only for use with spatial vectors. If you are using classic linear and angular vectors, then use getJacobianClassicDeriv(), getLinearJacobianDeriv(), or getAngularJacobianDeriv() instead.

See also
getJacobianSpatialDeriv()

Implements dart::dynamics::JacobianNode.

◆ getJacobianSpatialDeriv() [3/4]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobianSpatialDeriv ( const Eigen::Vector3d &  _offset,
const Frame _inCoordinatesOf 
) const
finaloverridevirtualinherited

A version of getJacobianSpatialDeriv(const Eigen::Vector3d&) that allows an arbitrary coordinate Frame to be specified.

Implements dart::dynamics::JacobianNode.

◆ getJacobianSpatialDeriv() [4/4]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getJacobianSpatialDeriv ( const Frame _inCoordinatesOf) const
finaloverridevirtualinherited

A version of getJacobianSpatialDeriv() that can return the Jacobian in coordinates of any Frame.

NOTE: This Jacobian Derivative is only for use with spatial vectors. If you are using classical linear and angular vectors, then use getJacobianClassicDeriv(), getLinearJacobianDeriv(), or getAngularJacobianDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getKineticEnergy()

double dart::dynamics::BodyNode::getKineticEnergy ( ) const
virtual

Return kinetic energy.

◆ getLinearAcceleration() [1/2]

Eigen::Vector3d dart::dynamics::Frame::getLinearAcceleration ( const Eigen::Vector3d &  _offset,
const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const
inherited

◆ getLinearAcceleration() [2/2]

Eigen::Vector3d dart::dynamics::Frame::getLinearAcceleration ( const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const
inherited

Get the linear portion of classical acceleration of this Frame relative to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getLinearJacobian() [1/2]

math::LinearJacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getLinearJacobian ( const Eigen::Vector3d &  _offset,
const Frame _inCoordinatesOf = Frame::World() 
) const
finaloverridevirtualinherited

Return the generalized Jacobian targeting an offset within the Frame of this BodyNode.

Implements dart::dynamics::JacobianNode.

◆ getLinearJacobian() [2/2]

math::LinearJacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getLinearJacobian ( const Frame _inCoordinatesOf = Frame::World()) const
finaloverridevirtualinherited

Return the linear Jacobian targeting the origin of this BodyNode.

You can specify a coordinate Frame to express the Jacobian in.

Implements dart::dynamics::JacobianNode.

◆ getLinearJacobianDeriv() [1/2]

math::LinearJacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getLinearJacobianDeriv ( const Eigen::Vector3d &  _offset,
const Frame _inCoordinatesOf = Frame::World() 
) const
finaloverridevirtualinherited

A version of getLinearJacobianDeriv() that can compute the Jacobian for an offset within the Frame of this BodyNode.

The offset must be expressed in coordinates of this BodyNode Frame.

NOTE: Since this is a classical time derivative, it should be used with classical linear vectors. If you are using spatial vectors, use getJacobianSpatialDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getLinearJacobianDeriv() [2/2]

math::LinearJacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getLinearJacobianDeriv ( const Frame _inCoordinatesOf = Frame::World()) const
finaloverridevirtualinherited

Return the linear Jacobian (classical) time derivative, in terms of any coordinate Frame.

NOTE: Since this is a classical time derivative, it should be used with classical linear vectors. If you are using spatial vectors, use getJacobianSpatialDeriv() instead.

Implements dart::dynamics::JacobianNode.

◆ getLinearMomentum()

Eigen::Vector3d dart::dynamics::BodyNode::getLinearMomentum ( ) const

Return linear momentum.

◆ getLinearVelocity() [1/2]

Eigen::Vector3d dart::dynamics::Frame::getLinearVelocity ( const Eigen::Vector3d &  _offset,
const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const
inherited

Get the linear velocity of a point that is fixed in this Frame.

You can specify a relative Frame, and it can be expressed in the coordinates of any Frame.

◆ getLinearVelocity() [2/2]

Eigen::Vector3d dart::dynamics::Frame::getLinearVelocity ( const Frame _relativeTo = Frame::World(),
const Frame _inCoordinatesOf = Frame::World() 
) const
inherited

Get the linear portion of classical velocity of this Frame relative to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getLocalCOM()

const Eigen::Vector3d & dart::dynamics::BodyNode::getLocalCOM ( ) const

Return center of mass expressed in body frame.

◆ getMarker() [1/2]

Marker * dart::dynamics::BodyNode::getMarker ( std::size_t  index)

◆ getMarker() [2/2]

const Marker * dart::dynamics::BodyNode::getMarker ( std::size_t  index) const

◆ getMass()

double dart::dynamics::BodyNode::getMass ( ) const

Return the mass of the bodynode.

◆ getMomentOfInertia()

void dart::dynamics::BodyNode::getMomentOfInertia ( double &  _Ixx,
double &  _Iyy,
double &  _Izz,
double &  _Ixy,
double &  _Ixz,
double &  _Iyz 
) const

Return moment of inertia defined around the center of mass.

◆ getName() [1/2]

const std::string & dart::dynamics::BodyNode::getName ( ) const
overridevirtual

Get the name of this Node.

Implements dart::dynamics::Node.

◆ getName() [2/2]

virtual const std::string& dart::dynamics::Node::getName
inherited

Get the name of this Node.

◆ getNodeProperties()

std::unique_ptr< Node::Properties > dart::dynamics::Node::getNodeProperties ( ) const
virtualinherited

Get the Properties of this Node.

By default, this returns a nullptr which implies that the Node has no properties.

◆ getNodeState()

std::unique_ptr< Node::State > dart::dynamics::Node::getNodeState ( ) const
virtualinherited

Get the State of this Node.

By default, this returns a nullptr which implies that the Node is stateless.

◆ getNumChildBodyNodes()

std::size_t dart::dynamics::BodyNode::getNumChildBodyNodes ( ) const

Return the number of child BodyNodes.

◆ getNumChildEntities()

std::size_t dart::dynamics::Frame::getNumChildEntities ( ) const
inherited

Get the number of Entities that are currently children of this Frame.

◆ getNumChildFrames()

std::size_t dart::dynamics::Frame::getNumChildFrames ( ) const
inherited

Get the number of Frames that are currently children of this Frame.

◆ getNumChildJoints()

std::size_t dart::dynamics::BodyNode::getNumChildJoints ( ) const

Return the number of child Joints.

◆ getNumDependentDofs()

std::size_t dart::dynamics::BodyNode::getNumDependentDofs ( ) const
overridevirtual

◆ getNumDependentGenCoords()

std::size_t dart::dynamics::BodyNode::getNumDependentGenCoords ( ) const
overridevirtual

The number of the generalized coordinates which affect this JacobianNode.

Implements dart::dynamics::JacobianNode.

◆ getNumEndEffectors()

std::size_t dart::dynamics::BodyNode::getNumEndEffectors ( ) const

◆ getNumMarkers()

std::size_t dart::dynamics::BodyNode::getNumMarkers ( ) const

◆ getNumShapeNodes()

std::size_t dart::dynamics::BodyNode::getNumShapeNodes ( ) const

◆ getNumShapeNodesWith()

template<class AspectT >
std::size_t dart::dynamics::BodyNode::getNumShapeNodesWith

Return the number of ShapeNodes containing given Aspect in this BodyNode.

◆ getOrCreateDestructor()

std::shared_ptr< NodeDestructor > dart::dynamics::Node::getOrCreateDestructor ( )
privateinherited

◆ getOrCreateIK()

const std::shared_ptr< InverseKinematics > & dart::dynamics::JacobianNode::getOrCreateIK ( )
inherited

Get a pointer to an IK module for this JacobianNode.

The IK module will be generated if one does not already exist. This function is actually the same as getIK(true).

◆ getParentBodyNode() [1/2]

BodyNode * dart::dynamics::BodyNode::getParentBodyNode ( )

Return the parent BodyNdoe of this BodyNode.

◆ getParentBodyNode() [2/2]

const BodyNode * dart::dynamics::BodyNode::getParentBodyNode ( ) const

Return the (const) parent BodyNode of this BodyNode.

◆ getParentFrame() [1/2]

Frame * dart::dynamics::Entity::getParentFrame ( )
inherited

Get the parent (reference) frame of this Entity.

◆ getParentFrame() [2/2]

const Frame * dart::dynamics::Entity::getParentFrame ( ) const
inherited

Get the parent (reference) frame of this Entity.

◆ getParentJoint() [1/2]

Joint * dart::dynamics::BodyNode::getParentJoint ( )

Return the parent Joint of this BodyNode.

◆ getParentJoint() [2/2]

const Joint * dart::dynamics::BodyNode::getParentJoint ( ) const

Return the (const) parent Joint of this BodyNode.

◆ getPartialAcceleration()

const Eigen::Vector6d & dart::dynamics::BodyNode::getPartialAcceleration ( ) const
overridevirtual

Return the partial acceleration of this body.

Implements dart::dynamics::Frame.

◆ getPotentialEnergy()

double dart::dynamics::BodyNode::getPotentialEnergy ( const Eigen::Vector3d &  _gravity) const
virtual

Return potential energy.

◆ getPrimaryRelativeAcceleration()

const Eigen::Vector6d & dart::dynamics::BodyNode::getPrimaryRelativeAcceleration ( ) const
overridevirtual

The Featherstone ABI algorithm exploits a component of the spatial acceleration which we refer to as the partial acceleration, accessible by getPartialAcceleration().

We save operations during our forward kinematics by computing and storing the partial acceleration separately from the rest of the Frame's acceleration. getPrimaryRelativeAcceleration() will return the portion of the relative spatial acceleration that is not contained in the partial acceleration. To get the full spatial acceleration of this Frame relative to its parent Frame, use getRelativeSpatialAcceleration(). To get the full spatial acceleration of this Frame relative to the World Frame, use getSpatialAcceleration().

Implements dart::dynamics::Frame.

◆ getRelativeSpatialAcceleration()

const Eigen::Vector6d & dart::dynamics::BodyNode::getRelativeSpatialAcceleration ( ) const
overridevirtual

Get the spatial acceleration of this Frame relative to its parent Frame, in the coordinates of this Frame.

Implements dart::dynamics::Frame.

◆ getRelativeSpatialVelocity()

const Eigen::Vector6d & dart::dynamics::BodyNode::getRelativeSpatialVelocity ( ) const
overridevirtual

Get the spatial velocity of this Frame relative to its parent Frame, in its own coordinates.

Implements dart::dynamics::Frame.

◆ getRelativeTransform()

const Eigen::Isometry3d & dart::dynamics::BodyNode::getRelativeTransform ( ) const
overridevirtual

Get the transform of this BodyNode with respect to its parent BodyNode, which is also its parent Frame.

Implements dart::dynamics::Frame.

◆ getRestitutionCoeff()

double dart::dynamics::BodyNode::getRestitutionCoeff ( ) const

Return coefficient of restitution.

◆ getShapeNode() [1/2]

ShapeNode * dart::dynamics::BodyNode::getShapeNode ( std::size_t  index)

◆ getShapeNode() [2/2]

const ShapeNode * dart::dynamics::BodyNode::getShapeNode ( std::size_t  index) const

◆ getShapeNodes() [1/2]

const std::vector< ShapeNode * > dart::dynamics::BodyNode::getShapeNodes ( )

Return the list of ShapeNodes.

◆ getShapeNodes() [2/2]

const std::vector< const ShapeNode * > dart::dynamics::BodyNode::getShapeNodes ( ) const

Return the list of (const) ShapeNodes.

◆ getShapeNodesWith() [1/2]

template<class AspectT >
const std::vector< ShapeNode * > dart::dynamics::BodyNode::getShapeNodesWith

Return the list of ShapeNodes containing given Aspect.

◆ getShapeNodesWith() [2/2]

template<class AspectT >
const std::vector< const ShapeNode * > dart::dynamics::BodyNode::getShapeNodesWith

Return the list of ShapeNodes containing given Aspect.

◆ getSkeleton() [1/2]

ConstSkeletonPtr dart::dynamics::BodyNode::getSkeleton ( ) const
overridevirtual

Return the Skeleton that this Node is attached to.

Reimplemented from dart::dynamics::Node.

◆ getSkeleton() [2/2]

SkeletonPtr dart::dynamics::BodyNode::getSkeleton ( )
overridevirtual

Return the Skeleton that this Node is attached to.

Reimplemented from dart::dynamics::Node.

◆ getSpatialAcceleration() [1/4]

const Eigen::Vector6d & dart::dynamics::Frame::getSpatialAcceleration ( ) const
inherited

Get the total spatial acceleration of this Frame in the coordinates of this Frame.

◆ getSpatialAcceleration() [2/4]

Eigen::Vector6d dart::dynamics::Frame::getSpatialAcceleration ( const Eigen::Vector3d &  _offset) const
inherited

Get the spatial acceleration of a fixed point in this Frame.

The acceleration is in coordinates of this Frame and is relative to the World Frame.

◆ getSpatialAcceleration() [3/4]

Eigen::Vector6d dart::dynamics::Frame::getSpatialAcceleration ( const Eigen::Vector3d &  _offset,
const Frame _relativeTo,
const Frame _inCoordinatesOf 
) const
inherited

Get the spatial acceleration of a fixed point in this Frame.

◆ getSpatialAcceleration() [4/4]

Eigen::Vector6d dart::dynamics::Frame::getSpatialAcceleration ( const Frame _relativeTo,
const Frame _inCoordinatesOf 
) const
inherited

Get the spatial acceleration of this Frame relative to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getSpatialInertia()

const Eigen::Matrix6d & dart::dynamics::BodyNode::getSpatialInertia ( ) const

Return spatial inertia.

◆ getSpatialVelocity() [1/4]

const Eigen::Vector6d & dart::dynamics::Frame::getSpatialVelocity ( ) const
inherited

Get the total spatial velocity of this Frame in the coordinates of this Frame.

◆ getSpatialVelocity() [2/4]

Eigen::Vector6d dart::dynamics::Frame::getSpatialVelocity ( const Eigen::Vector3d &  _offset) const
inherited

Get the spatial velocity of a fixed point in this Frame.

The velocity is in coordinates of this Frame and is relative to the World Frame.

◆ getSpatialVelocity() [3/4]

Eigen::Vector6d dart::dynamics::Frame::getSpatialVelocity ( const Eigen::Vector3d &  _offset,
const Frame _relativeTo,
const Frame _inCoordinatesOf 
) const
inherited

Get the spatial velocity of a fixed point in this Frame.

◆ getSpatialVelocity() [4/4]

Eigen::Vector6d dart::dynamics::Frame::getSpatialVelocity ( const Frame _relativeTo,
const Frame _inCoordinatesOf 
) const
inherited

Get the spatial velocity of this Frame relative to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getTransform() [1/2]

Eigen::Isometry3d dart::dynamics::Frame::getTransform ( const Frame _withRespectTo = Frame::World()) const
inherited

Get the transform of this Frame with respect to some other Frame.

◆ getTransform() [2/2]

Eigen::Isometry3d dart::dynamics::Frame::getTransform ( const Frame withRespectTo,
const Frame inCoordinatesOf 
) const
inherited

Get the transform of this Frame with respect to some other Frame.

It can be expressed in the coordinates of any Frame.

◆ getTreeIndex()

std::size_t dart::dynamics::BodyNode::getTreeIndex ( ) const

Return the index of the tree that this BodyNode belongs to.

◆ getVersion()

std::size_t dart::common::VersionCounter::getVersion ( ) const
virtualinherited

Get the version number of this object.

◆ getWorldJacobian() [1/2]

const math::Jacobian & dart::dynamics::BodyNode::getWorldJacobian ( ) const
finaloverridevirtual

Return the generalized Jacobian targeting the origin of this BodyNode.

The Jacobian is expressed in the World Frame.

Implements dart::dynamics::JacobianNode.

◆ getWorldJacobian() [2/2]

math::Jacobian dart::dynamics::TemplatedJacobianNode< BodyNode >::getWorldJacobian ( const Eigen::Vector3d &  _offset) const
finaloverridevirtualinherited

Return the generalized Jacobian targeting an offset in this JacobianNode.

The _offset is expected in coordinates of this BodyNode Frame. The Jacobian is expressed in the World Frame.

Implements dart::dynamics::JacobianNode.

◆ getWorldTransform()

const Eigen::Isometry3d & dart::dynamics::Frame::getWorldTransform ( ) const
inherited

Get the transform of this Frame with respect to the World Frame.

◆ incrementReferenceCount()

void dart::dynamics::SkeletonRefCountingBase::incrementReferenceCount ( ) const
privateinherited

Atomically increment the reference count for this BodyNode.

This should only be called by the BodyNodePtr class

◆ incrementVersion()

std::size_t dart::common::VersionCounter::incrementVersion ( )
virtualinherited

Increment the version for this object.

◆ init()

void dart::dynamics::BodyNode::init ( const SkeletonPtr _skeleton)
protectedvirtual

Initialize the vector members with proper sizes.

◆ isCollidable()

bool dart::dynamics::BodyNode::isCollidable ( ) const

Return true if this body can collide with others bodies.

◆ isColliding()

bool dart::dynamics::BodyNode::isColliding ( )

Return whether this body node is set to be colliding with other objects.

Returns
True if this body node is colliding.

◆ isFrame()

bool dart::dynamics::Entity::isFrame ( ) const
inherited

True iff this Entity is also a Frame.

◆ isQuiet()

bool dart::dynamics::Entity::isQuiet ( ) const
inherited

Returns true if this Entity is set to be quiet.

A quiet entity is unknown to its parent Frame. It will not be tracked by its parent; it will not receive notifications from its parent, and it will not be rendered. The advantage to a quiet Entity is that it has less overhead when constructing and deconstructing, which makes it more suitable for temporary objects.

◆ isReactive()

bool dart::dynamics::BodyNode::isReactive ( ) const

Return true if the body can react to force or constraint impulse.

A body node is reactive if the skeleton is mobile and the number of dependent generalized coordinates is non zero.

◆ isRemoved()

bool dart::dynamics::Node::isRemoved ( ) const
inherited

Returns true if this Node has been staged for removal from its BodyNode.

It will be deleted once all strong references to it expire. If it is an AccessoryNode, you can call reattach() to prevent that from happening.

◆ isShapeFrame()

bool dart::dynamics::Frame::isShapeFrame ( ) const
inherited

Returns true if this Frame is a ShapeFrame.

◆ isWorld()

bool dart::dynamics::Frame::isWorld ( ) const
inherited

Returns true if this Frame is the World Frame.

◆ matchNodes()

void dart::dynamics::BodyNode::matchNodes ( const BodyNode otherBodyNode)

Make the Nodes of this BodyNode match the Nodes of otherBodyNode.

All existing Nodes in this BodyNode will be removed.

◆ moveTo() [1/4]

bool dart::dynamics::BodyNode::moveTo ( BodyNode _newParent)

Remove this BodyNode and all of its children (recursively) from their current parent BodyNode, and move them to another parent BodyNode.

The new parent BodyNode can either be in a new Skeleton or the current one. If you pass in a nullptr, this BodyNode will become a new root BodyNode for its current Skeleton.

Using this function will result in changes to the indexing of (potentially) all BodyNodes and Joints in the current Skeleton, even if the BodyNodes are kept within the same Skeleton.

◆ moveTo() [2/4]

template<class JointType >
JointType * dart::dynamics::BodyNode::moveTo ( BodyNode _newParent,
const typename JointType::Properties &  _joint = typename JointType::Properties() 
)

A version of moveTo(BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode.

This function returns the pointer to the newly created Joint. The original parent Joint will be deleted.

This function can be used to change the Joint type of the parent Joint of this BodyNode, but note that the indexing of the BodyNodes and Joints in this Skeleton will still be changed, even if only the Joint type is changed.

◆ moveTo() [3/4]

bool dart::dynamics::BodyNode::moveTo ( const SkeletonPtr _newSkeleton,
BodyNode _newParent 
)

This is a version of moveTo(BodyNode*) that allows you to explicitly move this BodyNode into a different Skeleton.

The key difference for this version of the function is that you can make this BodyNode a root node in a different Skeleton, which is not something that can be done by the other version.

◆ moveTo() [4/4]

template<class JointType >
JointType * dart::dynamics::BodyNode::moveTo ( const SkeletonPtr _newSkeleton,
BodyNode _newParent,
const typename JointType::Properties &  _joint = typename JointType::Properties() 
)

A version of moveTo(SkeletonPtr, BodyNode*) that also changes the Joint type of the parent Joint of this BodyNode.

This function returns the pointer to the newly created Joint. The original Joint will be deleted.

◆ needsAccelerationUpdate()

bool dart::dynamics::Entity::needsAccelerationUpdate ( ) const
inherited

Returns true iff an acceleration update is needed for this Entity.

◆ needsTransformUpdate()

bool dart::dynamics::Entity::needsTransformUpdate ( ) const
inherited

Returns true iff a transform update is needed for this Entity.

◆ needsVelocityUpdate()

bool dart::dynamics::Entity::needsVelocityUpdate ( ) const
inherited

Returns true iff a velocity update is needed for this Entity.

◆ notifyAccelerationUpdate()

void dart::dynamics::Entity::notifyAccelerationUpdate ( )
virtualinherited

Notify the acceleration of this Entity that its parent Frame's acceleration is needed.

◆ notifyArticulatedInertiaUpdate()

void dart::dynamics::BodyNode::notifyArticulatedInertiaUpdate ( )

Notify the Skeleton that the tree of this BodyNode needs an articulated inertia update.

◆ notifyCoriolisUpdate()

void dart::dynamics::BodyNode::notifyCoriolisUpdate ( )

Tell the Skeleton that the coriolis forces need to be update.

◆ notifyExternalForcesUpdate()

void dart::dynamics::BodyNode::notifyExternalForcesUpdate ( )

Tell the Skeleton that the external forces need to be updated.

◆ notifyJacobianDerivUpdate()

void dart::dynamics::JacobianNode::notifyJacobianDerivUpdate ( )
inherited

Notify this BodyNode and all its descendents that their Jacobian derivatives need to be updated.

◆ notifyJacobianUpdate()

void dart::dynamics::JacobianNode::notifyJacobianUpdate ( )
inherited

Notify this BodyNode and all its descendents that their Jacobians need to be updated.

◆ notifyTransformUpdate()

void dart::dynamics::Entity::notifyTransformUpdate ( )
virtualinherited

Notify the transformation update of this Entity that its parent Frame's pose is needed.

◆ notifyVelocityUpdate()

void dart::dynamics::Entity::notifyVelocityUpdate ( )
virtualinherited

Notify the velocity update of this Entity that its parent Frame's velocity is needed.

◆ operator=()

BodyNode & dart::dynamics::BodyNode::operator= ( const BodyNode _otherBodyNode)

◆ processNewEntity()

void dart::dynamics::BodyNode::processNewEntity ( Entity _newChildEntity)
overrideprotectedvirtual

Separate generic child Entities from child BodyNodes for more efficient update notices.

Reimplemented from dart::dynamics::Frame.

◆ processRemovedEntity()

void dart::dynamics::BodyNode::processRemovedEntity ( Entity _oldChildEntity)
overrideprotectedvirtual

Remove this Entity from mChildBodyNodes or mNonBodyNodeEntities.

Reimplemented from dart::dynamics::Frame.

◆ registerNameChange()

std::string dart::dynamics::Node::registerNameChange ( const std::string &  newName)
protectedinherited

Inform the Skeleton that the name of this Node has changed.

If the name is already taken by another Node of the same type, then this function will return a modified version which is unique. If the name is not already taken, then it will just return the same name that the function was given.

◆ remove()

SkeletonPtr dart::dynamics::BodyNode::remove ( const std::string &  _name = "temporary")

Remove this BodyNode and all of its children (recursively) from their Skeleton.

If a BodyNodePtr that references this BodyNode (or any of its children) still exists, the subtree will be moved into a new Skeleton with the given name. If the returned SkeletonPtr goes unused and no relevant BodyNodePtrs are held anywhere, then this BodyNode and all its children will be deleted.

Note that this function is actually the same as split(), but given a different name for semantic reasons.

◆ removeAllShapeNodes()

void dart::dynamics::BodyNode::removeAllShapeNodes ( )

Remove all ShapeNodes from this BodyNode.

◆ removeAllShapeNodesWith()

template<class AspectT >
void dart::dynamics::BodyNode::removeAllShapeNodesWith

Remove all ShapeNodes containing given Aspect from this BodyNode.

◆ removeObserver()

void dart::common::Subject::removeObserver ( Observer _observer) const
protectedinherited

Remove an Observer from the list of Observers.

◆ sendDestructionNotification()

void dart::common::Subject::sendDestructionNotification ( ) const
protectedinherited

Send a destruction notification to all Observers.

This will cause all Observers to behave as if this Subject has been permanently deleted, so it should only be called when that behavior is desired.

◆ setAllNodeProperties()

void dart::dynamics::BodyNode::setAllNodeProperties ( const AllNodeProperties properties)

Set the Node::Properties of all Nodes attached to this BodyNode.

◆ setAllNodeStates()

void dart::dynamics::BodyNode::setAllNodeStates ( const AllNodeStates states)

Set the Node::State of all Nodes attached to this BodyNode.

◆ setAspectProperties()

void dart::dynamics::BodyNode::setAspectProperties ( const AspectProperties properties)

Set the AspectProperties of this BodyNode.

◆ setAspectState()

void dart::dynamics::BodyNode::setAspectState ( const AspectState state)

Set the AspectState of this BodyNode.

◆ setCollidable()

void dart::dynamics::BodyNode::setCollidable ( bool  _isCollidable)

Set whether this body node will collide with others in the world.

Parameters
[in]_isCollidableTrue to enable collisions

◆ setColliding()

void dart::dynamics::BodyNode::setColliding ( bool  _isColliding)

Set whether this body node is colliding with other objects.

Note that this status is set by the constraint solver during dynamics simulation but not by collision detector.

Parameters
[in]Trueif this body node is colliding.

◆ setConstraintImpulse()

void dart::dynamics::BodyNode::setConstraintImpulse ( const Eigen::Vector6d _constImp)

Set constraint impulse.

Parameters
[in]_constImpSpatial constraint impulse w.r.t. body frame

◆ setExtForce()

void dart::dynamics::BodyNode::setExtForce ( const Eigen::Vector3d &  _force,
const Eigen::Vector3d &  _offset = Eigen::Vector3d::Zero(),
bool  _isForceLocal = false,
bool  _isOffsetLocal = true 
)

Set Applying linear Cartesian forces to this node.

◆ setExtTorque()

void dart::dynamics::BodyNode::setExtTorque ( const Eigen::Vector3d &  _torque,
bool  _isLocal = false 
)

Set applying Cartesian torque to the node.

The torque in local coordinates is accumulated in mExtTorqueBody.

◆ setFrictionCoeff()

void dart::dynamics::BodyNode::setFrictionCoeff ( double  _coeff)

Set coefficient of friction in range of [0, ~].

◆ setGravityMode()

void dart::dynamics::BodyNode::setGravityMode ( bool  _gravityMode)

Set whether gravity affects this body.

Parameters
[in]_gravityModeTrue to enable gravity

◆ setInertia()

void dart::dynamics::BodyNode::setInertia ( const Inertia inertia)

Set the inertia data for this BodyNode.

◆ setLocalCOM()

void dart::dynamics::BodyNode::setLocalCOM ( const Eigen::Vector3d &  _com)

Set center of mass expressed in body frame.

◆ setMass()

void dart::dynamics::BodyNode::setMass ( double  mass)

Set the mass of the bodynode.

◆ setMomentOfInertia()

void dart::dynamics::BodyNode::setMomentOfInertia ( double  _Ixx,
double  _Iyy,
double  _Izz,
double  _Ixy = 0.0,
double  _Ixz = 0.0,
double  _Iyz = 0.0 
)

Set moment of inertia defined around the center of mass.

Principal moments of inertia (_Ixx, _Iyy, _Izz) must be positive or zero values.

◆ setName() [1/2]

const std::string & dart::dynamics::BodyNode::setName ( const std::string &  _name)
overridevirtual

Set name.

If the name is already taken, this will return an altered version which will be used by the Skeleton

Implements dart::dynamics::Node.

◆ setName() [2/2]

virtual const std::string& dart::dynamics::Node::setName
inherited

Set the name of this Node.

◆ setNodeProperties()

void dart::dynamics::Node::setNodeProperties ( const Properties properties)
virtualinherited

Set the Properties of this Node. By default, this does nothing.

◆ setNodeState()

void dart::dynamics::Node::setNodeState ( const State otherState)
virtualinherited

Set the State of this Node. By default, this does nothing.

◆ setProperties() [1/2]

void dart::dynamics::BodyNode::setProperties ( const AspectProperties _properties)

Set the UniqueProperties of this BodyNode.

◆ setProperties() [2/2]

void dart::dynamics::BodyNode::setProperties ( const CompositeProperties _properties)

Same as setCompositeProperties()

◆ setRestitutionCoeff()

void dart::dynamics::BodyNode::setRestitutionCoeff ( double  _coeff)

Set coefficient of restitution in range of [0, 1].

◆ setVersionDependentObject()

void dart::common::VersionCounter::setVersionDependentObject ( VersionCounter dependent)
protectedinherited

◆ split() [1/2]

SkeletonPtr dart::dynamics::BodyNode::split ( const std::string &  _skeletonName)

Remove this BodyNode and all of its children (recursively) from their current Skeleton and move them into a newly created Skeleton.

The newly created Skeleton will have the same Skeleton::Properties as the current Skeleton, except it will use the specified name. The return value is a shared_ptr to the newly created Skeleton.

Note that the parent Joint of this BodyNode will remain the same. If you want to change the Joint type of this BodyNode's parent Joint (for example, make it a FreeJoint), then use the templated split<JointType>() function.

◆ split() [2/2]

template<class JointType >
SkeletonPtr dart::dynamics::BodyNode::split ( const std::string &  _skeletonName,
const typename JointType::Properties &  _joint = typename JointType::Properties() 
)

A version of split(const std::string&) that also changes the Joint type of the parent Joint of this BodyNode.

◆ stageForRemoval()

void dart::dynamics::Node::stageForRemoval ( )
protectedinherited

When all external references to the Node disappear, it will be deleted.

◆ updateAccelerationFD()

void dart::dynamics::BodyNode::updateAccelerationFD ( )
protectedvirtual

Update spatial body acceleration for forward dynamics.

◆ updateAccelerationID()

void dart::dynamics::BodyNode::updateAccelerationID ( )
protectedvirtual

Update spatial body acceleration with the partial spatial body acceleration for inverse dynamics.

◆ updateArtInertia()

void dart::dynamics::BodyNode::updateArtInertia ( double  _timeStep) const
protectedvirtual

Update articulated body inertia for forward dynamics.

Parameters
[in]_timeStepRquired for implicit joint stiffness and damping.

◆ updateBiasForce()

void dart::dynamics::BodyNode::updateBiasForce ( const Eigen::Vector3d &  _gravity,
double  _timeStep 
)
protectedvirtual

Update bias force associated with the articulated body inertia for forward dynamics.

Parameters
[in]_gravityVector of gravitational acceleration
[in]_timeStepRquired for implicit joint stiffness and damping.

◆ updateBiasImpulse()

void dart::dynamics::BodyNode::updateBiasImpulse ( )
protectedvirtual

Update bias impulse associated with the articulated body inertia for impulse-based forward dynamics.

◆ updateBodyJacobian()

void dart::dynamics::BodyNode::updateBodyJacobian ( ) const
protected

Update body Jacobian.

getJacobian() calls this function if mIsBodyJacobianDirty is true.

◆ updateBodyJacobianSpatialDeriv()

void dart::dynamics::BodyNode::updateBodyJacobianSpatialDeriv ( ) const
protected

Update spatial time derivative of body Jacobian.

getJacobianSpatialTimeDeriv() calls this function if mIsBodyJacobianSpatialDerivDirty is true.

◆ updateCombinedVector()

void dart::dynamics::BodyNode::updateCombinedVector ( )
protectedvirtual

◆ updateConstrainedTerms()

void dart::dynamics::BodyNode::updateConstrainedTerms ( double  _timeStep)
protectedvirtual

Update constrained terms due to the constraint impulses for foward dynamics.

◆ updateInvAugMassMatrix()

void dart::dynamics::BodyNode::updateInvAugMassMatrix ( )
protectedvirtual

◆ updateInvMassMatrix()

void dart::dynamics::BodyNode::updateInvMassMatrix ( )
protectedvirtual

◆ updateJointForceFD()

void dart::dynamics::BodyNode::updateJointForceFD ( double  _timeStep,
bool  _withDampingForces,
bool  _withSpringForces 
)
protectedvirtual

Update the joint force for forward dynamics.

◆ updateJointForceID()

void dart::dynamics::BodyNode::updateJointForceID ( double  _timeStep,
bool  _withDampingForces,
bool  _withSpringForces 
)
protectedvirtual

Update the joint force for inverse dynamics.

◆ updateJointImpulseFD()

void dart::dynamics::BodyNode::updateJointImpulseFD ( )
protectedvirtual

Update the joint impulse for forward dynamics.

◆ updateMassMatrix()

void dart::dynamics::BodyNode::updateMassMatrix ( )
protectedvirtual

◆ updatePartialAcceleration()

void dart::dynamics::BodyNode::updatePartialAcceleration ( ) const
protectedvirtual

Update partial spatial body acceleration due to parent joint's velocity.

◆ updateTransform()

void dart::dynamics::BodyNode::updateTransform ( )
protectedvirtual

Update transformation.

◆ updateTransmittedForceFD()

void dart::dynamics::BodyNode::updateTransmittedForceFD ( )
protectedvirtual

Update spatial body force for forward dynamics.

The spatial body force is transmitted to this BodyNode from the parent body through the connecting joint. It is expressed in this BodyNode's frame.

◆ updateTransmittedForceID()

void dart::dynamics::BodyNode::updateTransmittedForceID ( const Eigen::Vector3d &  _gravity,
bool  _withExternalForces = false 
)
protectedvirtual

Update spatial body force for inverse dynamics.

The spatial body force is transmitted to this BodyNode from the parent body through the connecting joint. It is expressed in this BodyNode's frame.

◆ updateTransmittedImpulse()

void dart::dynamics::BodyNode::updateTransmittedImpulse ( )
protectedvirtual

Update spatial body force for impulse-based forward dynamics.

The spatial body impulse is transmitted to this BodyNode from the parent body through the connecting joint. It is expressed in this BodyNode's frame.

◆ updateVelocity()

void dart::dynamics::BodyNode::updateVelocity ( )
protectedvirtual

Update spatial body velocity.

◆ updateVelocityChangeFD()

void dart::dynamics::BodyNode::updateVelocityChangeFD ( )
protectedvirtual

Update spatical body velocity change for impluse-based forward dynamics.

◆ updateWorldJacobian()

void dart::dynamics::BodyNode::updateWorldJacobian ( ) const
protected

Update the World Jacobian.

The commonality of using the World Jacobian makes it worth caching.

◆ updateWorldJacobianClassicDeriv()

void dart::dynamics::BodyNode::updateWorldJacobianClassicDeriv ( ) const
protected

Update classic time derivative of body Jacobian.

getJacobianClassicDeriv() calls this function if mIsWorldJacobianClassicDerivDirty is true.

◆ World()

Frame * dart::dynamics::Frame::World ( )
staticinherited

Friends And Related Function Documentation

◆ EndEffector

friend class EndEffector
friend

◆ Joint

friend class Joint
friend

◆ Node

friend class Node
friend

◆ PointMass

friend class PointMass
friend

◆ Skeleton

friend class Skeleton
friend

◆ SoftBodyNode

friend class SoftBodyNode
friend

Member Data Documentation

◆ mAcceleration

Eigen::Vector6d dart::dynamics::Frame::mAcceleration
mutableprotectedinherited

Total acceleration of this Frame, in the coordinates of this Frame.

Do not use directly! Use getSpatialAcceleration() to access this quantity

◆ mAccelerationChangedSignal

EntitySignal dart::dynamics::Entity::mAccelerationChangedSignal
protectedinherited

Acceleration changed signal.

◆ mAmAttached

bool dart::dynamics::Node::mAmAttached
protectedinherited

bool that tracks whether this Node is attached to its BodyNode

◆ mAmFrame

bool dart::dynamics::Entity::mAmFrame
privateinherited

Whether or not this Entity is a Frame.

◆ mAmQuiet

const bool dart::dynamics::Entity::mAmQuiet
privateinherited

Whether or not this Entity is set to be quiet.

◆ mAmShapeFrame

bool dart::dynamics::Frame::mAmShapeFrame
privateinherited

Contains whether or not this is a ShapeFrame.

◆ mAmWorld

const bool dart::dynamics::Frame::mAmWorld
privateinherited

Contains whether or not this is the World Frame.

◆ mArbitrarySpatial

Eigen::Vector6d dart::dynamics::BodyNode::mArbitrarySpatial
protected

Cache data for arbitrary spatial value.

◆ mArtInertia

math::Inertia dart::dynamics::BodyNode::mArtInertia
mutableprotected

Articulated body inertia.

Do not use directly! Use getArticulatedInertia() to access this quantity

◆ mArtInertiaImplicit

math::Inertia dart::dynamics::BodyNode::mArtInertiaImplicit
mutableprotected

Articulated body inertia for implicit joint damping and spring forces.

DO not use directly! Use getArticulatedInertiaImplicit() to access this

◆ mAspectProperties

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
AspectProperties dart::common::EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT >::mAspectProperties
protectedinherited

Aspect::Properties data, directly accessible to your derived class.

◆ mAspectState

template<class DerivedT , typename StateDataT , typename PropertiesDataT , typename... CompositeBases>
AspectState dart::common::EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT >::mAspectState
protectedinherited

Aspect::State data, directly accessible to your derived class.

◆ mBiasForce

Eigen::Vector6d dart::dynamics::BodyNode::mBiasForce
protected

Bias force.

◆ mBiasImpulse

Eigen::Vector6d dart::dynamics::BodyNode::mBiasImpulse
protected

Impulsive bias force due to external impulsive force exerted on bodies of the parent skeleton.

◆ mBodyJacobian

math::Jacobian dart::dynamics::BodyNode::mBodyJacobian
mutableprotected

Body Jacobian.

Do not use directly! Use getJacobian() to access this quantity

◆ mBodyJacobianSpatialDeriv

math::Jacobian dart::dynamics::BodyNode::mBodyJacobianSpatialDeriv
mutableprotected

Spatial time derivative of body Jacobian.

Do not use directly! Use getJacobianSpatialDeriv() to access this quantity

◆ mBodyNode

BodyNode* dart::dynamics::Node::mBodyNode
protectedinherited

Pointer to the BodyNode that this Node is attached to.

◆ mCg_dV

Eigen::Vector6d dart::dynamics::BodyNode::mCg_dV
protected

Cache data for combined vector of the system.

◆ mCg_F

Eigen::Vector6d dart::dynamics::BodyNode::mCg_F
protected

◆ mChildBodyNodes

std::vector<BodyNode*> dart::dynamics::BodyNode::mChildBodyNodes
protected

Array of child body nodes.

◆ mChildEntities

std::set<Entity*> dart::dynamics::Frame::mChildEntities
protectedinherited

Container of this Frame's child Entities.

◆ mChildFrames

std::set<Frame*> dart::dynamics::Frame::mChildFrames
protectedinherited

Container of this Frame's child Frames.

◆ mChildJacobianNodes

std::unordered_set<JacobianNode*> dart::dynamics::JacobianNode::mChildJacobianNodes
protectedinherited

JacobianNode children that descend from this JacobianNode.

◆ mColShapeAddedSignal

ColShapeAddedSignal dart::dynamics::BodyNode::mColShapeAddedSignal
protected

Collision shape added signal.

◆ mColShapeRemovedSignal

ColShapeRemovedSignal dart::dynamics::BodyNode::mColShapeRemovedSignal
protected

Collision shape removed signal.

◆ mConstDependentDofs

std::vector<const DegreeOfFreedom*> dart::dynamics::BodyNode::mConstDependentDofs
protected

Same as mDependentDofs, but holds const pointers.

◆ mConstraintImpulse

Eigen::Vector6d dart::dynamics::BodyNode::mConstraintImpulse
protected

Constraint impulse: contact impulse, dynamic joint impulse.

◆ mDelV

Eigen::Vector6d dart::dynamics::BodyNode::mDelV
protected

Velocity change due to to external impulsive force exerted on bodies of the parent skeleton.

◆ mDependent

VersionCounter* dart::common::VersionCounter::mDependent
privateinherited

◆ mDependentDofs

std::vector<DegreeOfFreedom*> dart::dynamics::BodyNode::mDependentDofs
protected

A version of mDependentGenCoordIndices that holds DegreeOfFreedom pointers instead of indices.

◆ mDependentGenCoordIndices

std::vector<std::size_t> dart::dynamics::BodyNode::mDependentGenCoordIndices
protected

A increasingly sorted list of dependent dof indices.

◆ mDestructor

std::weak_ptr<NodeDestructor> dart::dynamics::Node::mDestructor
protectedinherited

weak pointer to the destructor for this Node.

We use a shared_ptr "destructor" class instead of managing Nodes directly with shared_ptrs because this scheme allows BodyNodes to circumvent the shared_ptr management by setting the mNode member of the Destructor to a nullptr. That way the BodyNode can never be deleted by its Destructor.

◆ mF

Eigen::Vector6d dart::dynamics::BodyNode::mF
protected

Transmitted wrench from parent to the bodynode expressed in body-fixed frame.

◆ mFext_F

Eigen::Vector6d dart::dynamics::BodyNode::mFext_F
protected

Cache data for external force vector of the system.

◆ mFgravity

Eigen::Vector6d dart::dynamics::BodyNode::mFgravity
protected

Spatial gravity force.

◆ mFrameChangedSignal

FrameChangedSignal dart::dynamics::Entity::mFrameChangedSignal
protectedinherited

Frame changed signal.

◆ mG_F

Eigen::Vector6d dart::dynamics::BodyNode::mG_F
protected

Cache data for gravity force vector of the system.

◆ mID

int dart::dynamics::BodyNode::mID
protected

A unique ID of this node globally.

◆ mIK

std::shared_ptr<InverseKinematics> dart::dynamics::JacobianNode::mIK
protectedinherited

Inverse kinematics module which gets lazily created upon request.

◆ mImpF

Eigen::Vector6d dart::dynamics::BodyNode::mImpF
protected

Generalized impulsive body force w.r.t. body frame.

◆ mIndexInBodyNode

std::size_t dart::dynamics::Node::mIndexInBodyNode
protectedinherited

The index of this Node within its vector in its BodyNode's NodeMap.

◆ mIndexInSkeleton

std::size_t dart::dynamics::BodyNode::mIndexInSkeleton
protected

Index of this BodyNode in its Skeleton.

◆ mIndexInTree

std::size_t dart::dynamics::BodyNode::mIndexInTree
protected

Index of this BodyNode in its Tree.

◆ mInvM_c

Eigen::Vector6d dart::dynamics::BodyNode::mInvM_c
protected

Cache data for inverse mass matrix of the system.

◆ mInvM_U

Eigen::Vector6d dart::dynamics::BodyNode::mInvM_U
protected

◆ mIsBodyJacobianDirty

bool dart::dynamics::JacobianNode::mIsBodyJacobianDirty
mutableprotectedinherited

Dirty flag for body Jacobian.

◆ mIsBodyJacobianSpatialDerivDirty

bool dart::dynamics::JacobianNode::mIsBodyJacobianSpatialDerivDirty
mutableprotectedinherited

Dirty flag for spatial time derivative of body Jacobian.

◆ mIsColliding

bool dart::dynamics::BodyNode::mIsColliding
protected

Whether the node is currently in collision with another node.

Deprecated:
DART_DEPRECATED(6.0) See #670 for more detail.

◆ mIsPartialAccelerationDirty

bool dart::dynamics::BodyNode::mIsPartialAccelerationDirty
mutableprotected

Is the partial acceleration vector dirty.

◆ mIsWorldJacobianClassicDerivDirty

bool dart::dynamics::JacobianNode::mIsWorldJacobianClassicDerivDirty
mutableprotectedinherited

Dirty flag for the classic time derivative of the Jacobian.

◆ mIsWorldJacobianDirty

bool dart::dynamics::JacobianNode::mIsWorldJacobianDirty
mutableprotectedinherited

Dirty flag for world Jacobian.

◆ mLockedSkeleton

std::shared_ptr<MutexedWeakSkeletonPtr> dart::dynamics::SkeletonRefCountingBase::mLockedSkeleton
protectedinherited

Shared reference to a weak_ptr of this BodyNode's Skeleton, along with a mutex to ensure thread safety.

This is used by WeakBodyNodePtrs to know when this BodyNode has expired.

◆ mM_dV

Eigen::Vector6d dart::dynamics::BodyNode::mM_dV
protected

Cache data for mass matrix of the system.

◆ mM_F

Eigen::Vector6d dart::dynamics::BodyNode::mM_F
protected

◆ mNameChangedSignal

NameChangedSignal dart::dynamics::Entity::mNameChangedSignal
protectedinherited

Name changed signal.

◆ mNeedAccelerationUpdate

bool dart::dynamics::Entity::mNeedAccelerationUpdate
mutableprotectedinherited

Does this Entity need an Acceleration update.

◆ mNeedTransformUpdate

bool dart::dynamics::Entity::mNeedTransformUpdate
mutableprotectedinherited

Does this Entity need a Transform update.

◆ mNeedVelocityUpdate

bool dart::dynamics::Entity::mNeedVelocityUpdate
mutableprotectedinherited

Does this Entity need a Velocity update.

◆ mNonBodyNodeEntities

std::set<Entity*> dart::dynamics::BodyNode::mNonBodyNodeEntities
protected

Array of child Entities that are not BodyNodes.

Organizing them separately allows some performance optimizations.

◆ mObservers

std::set<Observer*> dart::common::Subject::mObservers
mutableprotectedinherited

List of current Observers.

◆ mParentBodyNode

BodyNode* dart::dynamics::BodyNode::mParentBodyNode
protected

Parent body node.

◆ mParentFrame

Frame* dart::dynamics::Entity::mParentFrame
protectedinherited

Parent frame of this Entity.

◆ mParentJoint

Joint* dart::dynamics::BodyNode::mParentJoint
protected

Parent joint.

◆ mPartialAcceleration

Eigen::Vector6d dart::dynamics::BodyNode::mPartialAcceleration
mutableprotected

Partial spatial body acceleration due to parent joint's velocity.

Do not use directly! Use getPartialAcceleration() to access this quantity

◆ mReferenceCount

std::atomic<int> dart::dynamics::SkeletonRefCountingBase::mReferenceCount
mutableprotectedinherited

Reference count for the number of BodyNodePtrs that are referring to this BodyNode.

◆ mReferenceSkeleton

std::shared_ptr<Skeleton> dart::dynamics::SkeletonRefCountingBase::mReferenceSkeleton
mutableprotectedinherited

If mReferenceCount is zero, then mReferenceSkeleton will hold a nullptr.

If mReferenceCount is greater than zero, then mReferenceSkeleton will hold a shared_ptr to the Skeleton that this BodyNode belongs to. This is to keep this BodyNode alive, so long as a BodyNodePtr that references it exists.

◆ msBodyNodeCount

std::size_t dart::dynamics::BodyNode::msBodyNodeCount = 0
staticprotected

Counts the number of nodes globally.

◆ mSelfDestructor

std::shared_ptr<NodeDestructor> dart::dynamics::BodyNode::mSelfDestructor
private

Hold onto a reference to this BodyNode's own Destructor to make sure that it never gets destroyed.

◆ mSkeleton

std::weak_ptr<Skeleton> dart::dynamics::SkeletonRefCountingBase::mSkeleton
protectedinherited

Weak pointer to the Skeleton this BodyNode belongs to.

◆ mStructuralChangeSignal

StructuralChangeSignal dart::dynamics::BodyNode::mStructuralChangeSignal
protected

Structural change signal.

◆ mTransformUpdatedSignal

EntitySignal dart::dynamics::Entity::mTransformUpdatedSignal
protectedinherited

Transform changed signal.

◆ mTreeIndex

std::size_t dart::dynamics::BodyNode::mTreeIndex
protected

Index of this BodyNode's tree.

◆ mVelocity

Eigen::Vector6d dart::dynamics::Frame::mVelocity
mutableprotectedinherited

Total velocity of this Frame, in the coordinates of this Frame.

Do not use directly! Use getSpatialVelocity() to access this quantity

◆ mVelocityChangedSignal

EntitySignal dart::dynamics::Entity::mVelocityChangedSignal
protectedinherited

Velocity changed signal.

◆ mVersion

std::size_t dart::common::VersionCounter::mVersion
protectedinherited

◆ mWorldJacobian

math::Jacobian dart::dynamics::BodyNode::mWorldJacobian
mutableprotected

Cached World Jacobian.

Do not use directly! Use getJacobian() to access this quantity

◆ mWorldJacobianClassicDeriv

math::Jacobian dart::dynamics::BodyNode::mWorldJacobianClassicDeriv
mutableprotected

Classic time derivative of Body Jacobian.

Do not use directly! Use getJacobianClassicDeriv() to access this quantity

◆ mWorldTransform

Eigen::Isometry3d dart::dynamics::Frame::mWorldTransform
mutableprotectedinherited

World transform of this Frame.

This object is mutable to enable auto-updating to happen in the const member getWorldTransform() function

Do not use directly! Use getWorldTransform() to access this quantity

◆ onAccelerationChanged

common::SlotRegister<EntitySignal> dart::dynamics::Entity::onAccelerationChanged
inherited

Slot register for acceleration updated signal.

◆ onColShapeAdded

common::SlotRegister<ColShapeAddedSignal> dart::dynamics::BodyNode::onColShapeAdded

Slot register for collision shape added signal.

◆ onColShapeRemoved

common::SlotRegister<ColShapeRemovedSignal> dart::dynamics::BodyNode::onColShapeRemoved

Slot register for collision shape removed signal.

◆ onFrameChanged

common::SlotRegister<FrameChangedSignal> dart::dynamics::Entity::onFrameChanged
inherited

Slot register for frame changed signal.

◆ onNameChanged

common::SlotRegister<NameChangedSignal> dart::dynamics::Entity::onNameChanged
inherited

Slot register for name changed signal.

◆ onStructuralChange

common::SlotRegister<StructuralChangeSignal> dart::dynamics::BodyNode::onStructuralChange
mutable

Raised when (1) parent BodyNode is changed, (2) moved between Skeletons, (3) parent Joint is changed.

◆ onTransformUpdated

common::SlotRegister<EntitySignal> dart::dynamics::Entity::onTransformUpdated
inherited

Slot register for transform updated signal.

◆ onVelocityChanged

common::SlotRegister<EntitySignal> dart::dynamics::Entity::onVelocityChanged
inherited

Slot register for velocity updated signal.