DART  6.6.2
dart::dynamics::Joint Class Referenceabstract

class Joint More...

#include <Joint.hpp>

Inheritance diagram for dart::dynamics::Joint:
dart::common::Subject dart::common::VersionCounter dart::common::EmbedProperties< Joint, detail::JointProperties > dart::common::RequiresAspect< OtherRequiredAspects > dart::dynamics::ZeroDofJoint dart::dynamics::WeldJoint

Classes

struct  ExtendedProperties
 

Public Types

using CompositeProperties = common::Composite::Properties
 
using Properties = detail::JointProperties
 
typedef detail::ActuatorType ActuatorType
 
using Derived = Joint
 
using Aspect = common::EmbeddedPropertiesAspect< Derived, detail::JointProperties >
 
using AspectProperties = typename Aspect::Properties
 
using AspectPropertiesData = typename Aspect::PropertiesData
 
using Base = common::RequiresAspect< Aspect >
 

Public Member Functions

bool hasJointAspect () const
 Check if this Composite currently has JointAspect . More...
 
AspectgetJointAspect ()
 Get a(an) JointAspect from this Composite. More...
 
const AspectgetJointAspect () const
 Get a(an) JointAspect from this Composite. More...
 
AspectgetJointAspect (const bool createIfNull)
 Get a(an) JointAspect from this Composite. More...
 
void setJointAspect (const Aspect *aspect)
 Make a clone of JointAspect and place the clone into this Composite. More...
 
void setJointAspect (std::unique_ptr< Aspect > &&aspect)
 Use move semantics to place JointAspect into this Composite. More...
 
template<typename ... Args>
AspectcreateJointAspect (Args &&... args)
 Construct a(an) JointAspect inside of this Composite. More...
 
void removeJointAspect ()
 Remove a(an) JointAspect from this Composite. More...
 
std::unique_ptr< AspectreleaseJointAspect ()
 Remove a(an) JointAspect from this Composite, but return its unique_ptr instead of letting it be deleted. More...
 
 Joint (const Joint &)=delete
 
virtual ~Joint ()
 Destructor. More...
 
void setProperties (const Properties &properties)
 Set the Properties of this Joint. More...
 
void setAspectProperties (const AspectProperties &properties)
 Set the AspectProperties of this Joint. More...
 
const PropertiesgetJointProperties () const
 Get the Properties of this Joint. More...
 
void copy (const Joint &_otherJoint)
 Copy the properties of another Joint. More...
 
void copy (const Joint *_otherJoint)
 Copy the properties of another Joint. More...
 
Jointoperator= (const Joint &_otherJoint)
 Same as copy(const Joint&) More...
 
const std::string & setName (const std::string &_name, bool _renameDofs=true)
 Set joint name and return the name. More...
 
const std::string & getName () const
 Get joint name. More...
 
virtual const std::string & getType () const =0
 Gets a string representing the joint type. More...
 
void setActuatorType (ActuatorType _actuatorType)
 Set actuator type. More...
 
ActuatorType getActuatorType () const
 Get actuator type. More...
 
bool isKinematic () const
 Return true if this joint is kinematic joint. More...
 
bool isDynamic () const
 Return true if this joint is dynamic joint. More...
 
BodyNodegetChildBodyNode ()
 Get the child BodyNode of this Joint. More...
 
const BodyNodegetChildBodyNode () const
 Get the (const) child BodyNode of this Joint. More...
 
BodyNodegetParentBodyNode ()
 Get the parent BodyNode of this Joint. More...
 
const BodyNodegetParentBodyNode () const
 Get the (const) parent BodyNode of this Joint. More...
 
SkeletonPtr getSkeleton ()
 Get the Skeleton that this Joint belongs to. More...
 
std::shared_ptr< const SkeletongetSkeleton () const
 Get the (const) Skeleton that this Joint belongs to. More...
 
virtual void setTransformFromParentBodyNode (const Eigen::Isometry3d &_T)
 Set transformation from parent body node to this joint. More...
 
virtual void setTransformFromChildBodyNode (const Eigen::Isometry3d &_T)
 Set transformation from child body node to this joint. More...
 
const Eigen::Isometry3d & getTransformFromParentBodyNode () const
 Get transformation from parent body node to this joint. More...
 
const Eigen::Isometry3d & getTransformFromChildBodyNode () const
 Get transformation from child body node to this joint. More...
 
void setPositionLimitEnforced (bool _isPositionLimitEnforced)
 Set to enforce joint position limit. More...
 
bool isPositionLimitEnforced () const
 Get whether enforcing joint position limit. More...
 
virtual std::size_t getIndexInSkeleton (std::size_t _index) const =0
 Get a unique index in skeleton of a generalized coordinate in this Joint. More...
 
virtual std::size_t getIndexInTree (std::size_t _index) const =0
 Get a unique index in the kinematic tree of a generalized coordinate in this Joint. More...
 
std::size_t getJointIndexInSkeleton () const
 Get the index of this Joint within its Skeleton. More...
 
std::size_t getJointIndexInTree () const
 Get the index of this Joint within its tree. More...
 
std::size_t getTreeIndex () const
 Get the index of the tree that this Joint belongs to. More...
 
virtual DegreeOfFreedomgetDof (std::size_t _index)=0
 Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint. More...
 
virtual const DegreeOfFreedomgetDof (std::size_t _index) const =0
 Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint. More...
 
virtual const std::string & setDofName (std::size_t _index, const std::string &_name, bool _preserveName=true)=0
 Alternative to DegreeOfFreedom::setName() More...
 
virtual void preserveDofName (std::size_t _index, bool _preserve)=0
 Alternative to DegreeOfFreedom::preserveName() More...
 
virtual bool isDofNamePreserved (std::size_t _index) const =0
 Alternative to DegreeOfFreedom::isNamePreserved() More...
 
virtual const std::string & getDofName (std::size_t _index) const =0
 Alternative to DegreeOfFreedom::getName() More...
 
virtual std::size_t getNumDofs () const =0
 Get number of generalized coordinates. More...
 
double getPotentialEnergy () const
 Get potential energy. More...
 
virtual double computePotentialEnergy () const =0
 Compute and return the potential energy. More...
 
const Eigen::Isometry3d & getLocalTransform () const
 Deprecated. Use getRelativeTransform() instead. More...
 
const Eigen::Vector6dgetLocalSpatialVelocity () const
 Deprecated. Use getLocalSpatialVelocity() instead. More...
 
const Eigen::Vector6dgetLocalSpatialAcceleration () const
 Deprecated. Use getLocalSpatialAcceleration() instead. More...
 
const Eigen::Vector6dgetLocalPrimaryAcceleration () const
 Deprecated. Use getLocalPrimaryAcceleration() instead. More...
 
const math::Jacobian getLocalJacobian () const
 Deprecated. Use getRelativeJacobian() instead. More...
 
math::Jacobian getLocalJacobian (const Eigen::VectorXd &positions) const
 Deprecated. Use getRelativeJacobian() instead. More...
 
const math::Jacobian getLocalJacobianTimeDeriv () const
 Deprecated. Use getRelativeJacobianTimeDeriv() instead. More...
 
const Eigen::Isometry3d & getRelativeTransform () const
 Get transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
const Eigen::Vector6dgetRelativeSpatialVelocity () const
 Get spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
const Eigen::Vector6dgetRelativeSpatialAcceleration () const
 Get spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
const Eigen::Vector6dgetRelativePrimaryAcceleration () const
 Get J * \ddot{q} of this joint. More...
 
virtual const math::Jacobian getRelativeJacobian () const =0
 Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual math::Jacobian getRelativeJacobian (const Eigen::VectorXd &positions) const =0
 Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual const math::Jacobian getRelativeJacobianTimeDeriv () const =0
 Get time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual Eigen::Vector6d getBodyConstraintWrench () const =0
 Get constraint wrench expressed in body node frame. 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...
 
const AspectPropertiesgetAspectProperties () const
 
Command
virtual void setCommand (std::size_t _index, double _command)=0
 Set a single command. More...
 
virtual double getCommand (std::size_t _index) const =0
 Get a single command. More...
 
virtual void setCommands (const Eigen::VectorXd &_commands)=0
 Set all commands for this Joint. More...
 
virtual Eigen::VectorXd getCommands () const =0
 Get all commands for this Joint. More...
 
virtual void resetCommands ()=0
 Set all the commands for this Joint to zero. More...
 
Position
virtual void setPosition (std::size_t _index, double _position)=0
 Set the position of a single generalized coordinate. More...
 
virtual double getPosition (std::size_t _index) const =0
 Get the position of a single generalized coordinate. More...
 
virtual void setPositions (const Eigen::VectorXd &_positions)=0
 Set the positions of all generalized coordinates in this Joint. More...
 
virtual Eigen::VectorXd getPositions () const =0
 Get the positions of all generalized coordinates in this Joint. More...
 
virtual void setPositionLowerLimit (std::size_t _index, double _position)=0
 Set lower limit for position. More...
 
virtual double getPositionLowerLimit (std::size_t _index) const =0
 Get lower limit for position. More...
 
virtual void setPositionLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the position lower limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getPositionLowerLimits () const =0
 Get the position lower limits of all the generalized coordinates. More...
 
virtual void setPositionUpperLimit (std::size_t _index, double _position)=0
 Set upper limit for position. More...
 
virtual double getPositionUpperLimit (std::size_t _index) const =0
 Get upper limit for position. More...
 
virtual void setPositionUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the position upper limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getPositionUpperLimits () const =0
 Get the position upper limits of all the generalized coordinates. More...
 
virtual bool isCyclic (std::size_t _index) const =0
 Get whether a generalized coordinate is cyclic. More...
 
virtual bool hasPositionLimit (std::size_t _index) const =0
 Get whether the position of a generalized coordinate has limits. More...
 
virtual void resetPosition (std::size_t _index)=0
 Set the position of this generalized coordinate to its initial position. More...
 
virtual void resetPositions ()=0
 Set the positions of all generalized coordinates in this Joint to their initial positions. More...
 
virtual void setInitialPosition (std::size_t _index, double _initial)=0
 Change the position that resetPositions() will give to this coordinate. More...
 
virtual double getInitialPosition (std::size_t _index) const =0
 Get the position that resetPosition() will give to this coordinate. More...
 
virtual void setInitialPositions (const Eigen::VectorXd &_initial)=0
 Change the positions that resetPositions() will give to this Joint's coordinates. More...
 
virtual Eigen::VectorXd getInitialPositions () const =0
 Get the positions that resetPositions() will give to this Joint's coordinates. More...
 
Velocity
virtual void setVelocity (std::size_t _index, double _velocity)=0
 Set the velocity of a single generalized coordinate. More...
 
virtual double getVelocity (std::size_t _index) const =0
 Get the velocity of a single generalized coordinate. More...
 
virtual void setVelocities (const Eigen::VectorXd &_velocities)=0
 Set the velocities of all generalized coordinates in this Joint. More...
 
virtual Eigen::VectorXd getVelocities () const =0
 Get the velocities of all generalized coordinates in this Joint. More...
 
virtual void setVelocityLowerLimit (std::size_t _index, double _velocity)=0
 Set lower limit for velocity. More...
 
virtual double getVelocityLowerLimit (std::size_t _index) const =0
 Get lower limit for velocity. More...
 
virtual void setVelocityLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the velocity lower limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getVelocityLowerLimits () const =0
 Get the velocity lower limits of all the generalized coordinates. More...
 
virtual void setVelocityUpperLimit (std::size_t _index, double _velocity)=0
 Set upper limit for velocity. More...
 
virtual double getVelocityUpperLimit (std::size_t _index) const =0
 Get upper limit for velocity. More...
 
virtual void setVelocityUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the velocity upper limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getVelocityUpperLimits () const =0
 Get the velocity upper limits of all the generalized coordinates. More...
 
virtual void resetVelocity (std::size_t _index)=0
 Set the velocity of a generalized coordinate in this Joint to its initial velocity. More...
 
virtual void resetVelocities ()=0
 Set the velocities of all generalized coordinates in this Joint to their initial velocities. More...
 
virtual void setInitialVelocity (std::size_t _index, double _initial)=0
 Change the velocity that resetVelocity() will give to this coordinate. More...
 
virtual double getInitialVelocity (std::size_t _index) const =0
 Get the velocity that resetVelocity() will give to this coordinate. More...
 
virtual void setInitialVelocities (const Eigen::VectorXd &_initial)=0
 Change the velocities that resetVelocities() will give to this Joint's coordinates. More...
 
virtual Eigen::VectorXd getInitialVelocities () const =0
 Get the velocities that resetVelocities() will give to this Joint's coordinates. More...
 
Acceleration
virtual void setAcceleration (std::size_t _index, double _acceleration)=0
 Set the acceleration of a single generalized coordinate. More...
 
virtual double getAcceleration (std::size_t _index) const =0
 Get the acceleration of a single generalized coordinate. More...
 
virtual void setAccelerations (const Eigen::VectorXd &_accelerations)=0
 Set the accelerations of all generalized coordinates in this Joint. More...
 
virtual Eigen::VectorXd getAccelerations () const =0
 Get the accelerations of all generalized coordinates in this Joint. More...
 
virtual void resetAccelerations ()=0
 Set the accelerations of all generalized coordinates in this Joint to zero. More...
 
virtual void setAccelerationLowerLimit (std::size_t _index, double _acceleration)=0
 Set lower limit for acceleration. More...
 
virtual double getAccelerationLowerLimit (std::size_t _index) const =0
 Get lower limit for acceleration. More...
 
virtual void setAccelerationLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the acceleration upper limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getAccelerationLowerLimits () const =0
 Get the acceleration upper limits of all the generalized coordinates. More...
 
virtual void setAccelerationUpperLimit (std::size_t _index, double _acceleration)=0
 Set upper limit for acceleration. More...
 
virtual double getAccelerationUpperLimit (std::size_t _index) const =0
 Get upper limit for acceleration. More...
 
virtual void setAccelerationUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the acceleration upper limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getAccelerationUpperLimits () const =0
 Get the acceleration upper limits of all the generalized coordinates. More...
 
Force
virtual void setForce (std::size_t _index, double _force)=0
 Set the force of a single generalized coordinate. More...
 
virtual double getForce (std::size_t _index) const =0
 Get the force of a single generalized coordinate. More...
 
virtual void setForces (const Eigen::VectorXd &_forces)=0
 Set the forces of all generalized coordinates in this Joint. More...
 
virtual Eigen::VectorXd getForces () const =0
 Get the forces of all generalized coordinates in this Joint. More...
 
virtual void resetForces ()=0
 Set the forces of all generalized coordinates in this Joint to zero. More...
 
virtual void setForceLowerLimit (std::size_t _index, double _force)=0
 Set lower limit for force. More...
 
virtual double getForceLowerLimit (std::size_t _index) const =0
 Get lower limit for force. More...
 
virtual void setForceLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the force upper limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getForceLowerLimits () const =0
 Get the force upper limits of all the generalized coordinates. More...
 
virtual void setForceUpperLimit (std::size_t _index, double _force)=0
 Set upper limit for force. More...
 
virtual double getForceUpperLimit (std::size_t _index) const =0
 Get upper limit for force. More...
 
virtual void setForceUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the force upper limits of all the generalized coordinates. More...
 
virtual Eigen::VectorXd getForceUpperLimits () const =0
 Get the force upper limits of all the generalized coordinates. More...
 
Sanity Check
bool checkSanity (bool _printWarnings=true) const
 Returns false if the initial position or initial velocity are outside of limits. More...
 
Velocity change
virtual void setVelocityChange (std::size_t _index, double _velocityChange)=0
 Set a single velocity change. More...
 
virtual double getVelocityChange (std::size_t _index) const =0
 Get a single velocity change. More...
 
virtual void resetVelocityChanges ()=0
 Set zero all the velocity change. More...
 
Constraint impulse
virtual void setConstraintImpulse (std::size_t _index, double _impulse)=0
 Set a single constraint impulse. More...
 
virtual double getConstraintImpulse (std::size_t _index) const =0
 Get a single constraint impulse. More...
 
virtual void resetConstraintImpulses ()=0
 Set zero all the constraint impulses. More...
 
Integration and finite difference
virtual void integratePositions (double _dt)=0
 Integrate positions using Euler method. More...
 
virtual void integrateVelocities (double _dt)=0
 Integrate velocities using Euler method. More...
 
virtual Eigen::VectorXd getPositionDifferences (const Eigen::VectorXd &_q2, const Eigen::VectorXd &_q1) const =0
 Return the difference of two generalized coordinates which are measured in the configuration space of this Skeleton. More...
 
Passive forces - spring, viscous friction, Coulomb friction
virtual void setSpringStiffness (std::size_t _index, double _k)=0
 Set stiffness of joint spring force. More...
 
virtual double getSpringStiffness (std::size_t _index) const =0
 Get stiffness of joint spring force. More...
 
virtual void setRestPosition (std::size_t _index, double _q0)=0
 Set rest position of spring force. More...
 
virtual double getRestPosition (std::size_t _index) const =0
 Get rest position of spring force. More...
 
virtual void setDampingCoefficient (std::size_t _index, double _coeff)=0
 Set coefficient of joint damping (viscous friction) force. More...
 
virtual double getDampingCoefficient (std::size_t _index) const =0
 Get coefficient of joint damping (viscous friction) force. More...
 
virtual void setCoulombFriction (std::size_t _index, double _friction)=0
 Set joint Coulomb friction froce. More...
 
virtual double getCoulombFriction (std::size_t _index) const =0
 Get joint Coulomb friction froce. More...
 
Update Notifiers

Get spring force

We apply spring force in implicit manner. The spring force is F = -(springStiffness * q(k+1)), where q(k+1) is approximated as q(k) + h * dq(k) * h^2 * ddq(k). Since, in the recursive forward dynamics algorithm, ddq(k) is unknown variable that we want to obtain as the result, the spring force here is just F = -springStiffness * (q(k) + h * dq(k)) and -springStiffness * h^2 * ddq(k) term is rearranged at the recursive forward dynamics algorithm, and it affects on the articulated inertia.

See also
BodyNode::updateArticulatedInertia(double).
Parameters
[in]_timeStepTime step used for approximating q(k+1). Get damping force

We apply the damping force in implicit manner. The damping force is F = -(dampingCoefficient * dq(k+1)), where dq(k+1) is approximated as dq(k) + h * ddq(k). Since, in the recursive forward dynamics algorithm, ddq(k) is unknown variable that we want to obtain as the result, the damping force here is just F = -(dampingCoefficient * dq(k)) and -dampingCoefficient * h * ddq(k) term is rearranged at the recursive forward dynamics algorithm, and it affects on the articulated inertia.

See also
BodyNode::updateArticulatedInertia(double).
void notifyPositionUpdate ()
 Notify that a position has updated. More...
 
void notifyPositionUpdated ()
 Notify that a position has updated. More...
 
void notifyVelocityUpdate ()
 Notify that a velocity has updated. More...
 
void notifyVelocityUpdated ()
 Notify that a velocity has updated. More...
 
void notifyAccelerationUpdate ()
 Notify that an acceleration has updated. More...
 
void notifyAccelerationUpdated ()
 Notify that an acceleration has updated. More...
 

Static Public Attributes

static constexpr ActuatorType FORCE = detail::FORCE
 
static constexpr ActuatorType PASSIVE = detail::PASSIVE
 
static constexpr ActuatorType SERVO = detail::SERVO
 
static constexpr ActuatorType ACCELERATION = detail::ACCELERATION
 
static constexpr ActuatorType VELOCITY = detail::VELOCITY
 
static constexpr ActuatorType LOCKED = detail::LOCKED
 
static const ActuatorType DefaultActuatorType = detail::DefaultActuatorType
 Default actuator type. More...
 

Protected Member Functions

 Joint ()
 Constructor called by inheriting class. More...
 
virtual Jointclone () const =0
 Create a clone of this Joint. More...
 
virtual void registerDofs ()=0
 Called by the Skeleton class. More...
 
DegreeOfFreedomcreateDofPointer (std::size_t _indexInJoint)
 Create a DegreeOfFreedom pointer. More...
 
virtual void updateDegreeOfFreedomNames ()=0
 Update the names of the joint's degrees of freedom. 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...
 
void setVersionDependentObject (VersionCounter *dependent)
 
Recursive dynamics routines
void updateLocalTransform () const
 Deprecated. Use updateRelativeTransform() instead. More...
 
void updateLocalSpatialVelocity () const
 Deprecated. Use updateRelativeSpatialVelocity() instead. More...
 
void updateLocalSpatialAcceleration () const
 Deprecated. Use updateRelativeSpatialAcceleration() instead. More...
 
void updateLocalPrimaryAcceleration () const
 Deprecated. Use updateRelativePrimaryAcceleration() instead. More...
 
void updateLocalJacobian (bool mandatory=true) const
 Deprecated. Use updateRelativeJacobian() instead. More...
 
void updateLocalJacobianTimeDeriv () const
 Deprecated. Use updateRelativeJacobianTimeDeriv() instead. More...
 
virtual void updateRelativeTransform () const =0
 Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual void updateRelativeSpatialVelocity () const =0
 Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual void updateRelativeSpatialAcceleration () const =0
 Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual void updateRelativePrimaryAcceleration () const =0
 Update J * \ddot{q} of this joint. More...
 
virtual void updateRelativeJacobian (bool mandatory=true) const =0
 Update spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
virtual void updateRelativeJacobianTimeDeriv () const =0
 Update time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
void updateArticulatedInertia () const
 Tells the Skeleton to update the articulated inertia if it needs updating. More...
 
virtual void addVelocityTo (Eigen::Vector6d &_vel)=0
 Add joint velocity to _vel. More...
 
virtual void setPartialAccelerationTo (Eigen::Vector6d &_partialAcceleration, const Eigen::Vector6d &_childVelocity)=0
 Set joint partial acceleration to _partialAcceleration. More...
 
virtual void addAccelerationTo (Eigen::Vector6d &_acc)=0
 Add joint acceleration to _acc. More...
 
virtual void addVelocityChangeTo (Eigen::Vector6d &_velocityChange)=0
 Add joint velocity change to _velocityChange. More...
 
virtual void addChildArtInertiaTo (Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia)=0
 Add child's articulated inertia to parent's one. More...
 
virtual void addChildArtInertiaImplicitTo (Eigen::Matrix6d &_parentArtInertiaImplicit, const Eigen::Matrix6d &_childArtInertiaImplicit)=0
 Add child's articulated inertia to parent's one. Forward dynamics routine. More...
 
virtual void updateInvProjArtInertia (const Eigen::Matrix6d &_artInertia)=0
 Update inverse of projected articulated body inertia. More...
 
virtual void updateInvProjArtInertiaImplicit (const Eigen::Matrix6d &_artInertia, double _timeStep)=0
 Forward dynamics routine. More...
 
virtual void addChildBiasForceTo (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce, const Eigen::Vector6d &_childPartialAcc)=0
 Add child's bias force to parent's one. More...
 
virtual void addChildBiasImpulseTo (Eigen::Vector6d &_parentBiasImpulse, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasImpulse)=0
 Add child's bias impulse to parent's one. More...
 
virtual void updateTotalForce (const Eigen::Vector6d &_bodyForce, double _timeStep)=0
 Update joint total force. More...
 
virtual void updateTotalImpulse (const Eigen::Vector6d &_bodyImpulse)=0
 Update joint total impulse. More...
 
virtual void resetTotalImpulses ()=0
 Set total impulses to zero. More...
 
virtual void updateAcceleration (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
 Update joint acceleration. More...
 
virtual void updateVelocityChange (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_velocityChange)=0
 Update joint velocity change. More...
 
virtual void updateForceID (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces)=0
 Update joint force for inverse dynamics. More...
 
virtual void updateForceFD (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForcese, bool _withSpringForces)=0
 Update joint force for forward dynamics. More...
 
virtual void updateImpulseID (const Eigen::Vector6d &_bodyImpulse)=0
 Update joint impulses for inverse dynamics. More...
 
virtual void updateImpulseFD (const Eigen::Vector6d &_bodyImpulse)=0
 Update joint impulses for forward dynamics. More...
 
virtual void updateConstrainedTerms (double _timeStep)=0
 Update constrained terms for forward dynamics. More...
 
Recursive algorithm routines for equations of motion
virtual void addChildBiasForceForInvMassMatrix (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
 Add child's bias force to parent's one. More...
 
virtual void addChildBiasForceForInvAugMassMatrix (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
 Add child's bias force to parent's one. More...
 
virtual void updateTotalForceForInvMassMatrix (const Eigen::Vector6d &_bodyForce)=0
 
virtual void getInvMassMatrixSegment (Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
 
virtual void getInvAugMassMatrixSegment (Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
 
virtual void addInvMassMatrixSegmentTo (Eigen::Vector6d &_acc)=0
 
virtual Eigen::VectorXd getSpatialToGeneralized (const Eigen::Vector6d &_spatial)=0
 

Protected Attributes

BodyNodemChildBodyNode
 Child BodyNode pointer that this Joint belongs to. More...
 
Eigen::Isometry3d mT
 Relative transformation of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
Eigen::Vector6d mSpatialVelocity
 Relative spatial velocity from parent BodyNode to child BodyNode where the velocity is expressed in child body Frame. More...
 
Eigen::Vector6d mSpatialAcceleration
 Relative spatial acceleration from parent BodyNode to child BodyNode where the acceleration is expressed in the child body Frame. More...
 
Eigen::Vector6d mPrimaryAcceleration
 J * q_dd. More...
 
bool mNeedTransformUpdate
 True iff this joint's position has changed since the last call to getRelativeTransform() More...
 
bool mNeedSpatialVelocityUpdate
 True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVelocity() More...
 
bool mNeedSpatialAccelerationUpdate
 True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativeSpatialAcceleration() More...
 
bool mNeedPrimaryAccelerationUpdate
 True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativePrimaryAcceleration() More...
 
bool mIsRelativeJacobianDirty
 True iff this joint's relative Jacobian has not been updated since the last position change. More...
 
bool mIsRelativeJacobianTimeDerivDirty
 True iff this joint's relative Jacobian time derivative has not been updated since the last position or velocity change. More...
 
std::set< Observer * > mObservers
 List of current Observers. More...
 
std::size_t mVersion
 
AspectProperties mAspectProperties
 Aspect::Properties data, directly accessible to your derived class. More...
 

Private Attributes

VersionCountermDependent
 

Friends

class BodyNode
 
class SoftBodyNode
 
class Skeleton
 

Detailed Description

class Joint

Member Typedef Documentation

◆ ActuatorType

◆ Aspect

◆ AspectProperties

using dart::common::EmbedProperties< Joint , detail::JointProperties >::AspectProperties = typename Aspect::Properties
inherited

◆ AspectPropertiesData

◆ Base

◆ CompositeProperties

◆ Derived

◆ Properties

Constructor & Destructor Documentation

◆ Joint() [1/2]

dart::dynamics::Joint::Joint ( const Joint )
delete

◆ ~Joint()

dart::dynamics::Joint::~Joint ( )
virtual

Destructor.

◆ Joint() [2/2]

dart::dynamics::Joint::Joint ( )
protected

Constructor called by inheriting class.

Member Function Documentation

◆ addAccelerationTo()

virtual void dart::dynamics::Joint::addAccelerationTo ( Eigen::Vector6d _acc)
protectedpure virtual

Add joint acceleration to _acc.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addChildArtInertiaImplicitTo()

virtual void dart::dynamics::Joint::addChildArtInertiaImplicitTo ( Eigen::Matrix6d _parentArtInertiaImplicit,
const Eigen::Matrix6d _childArtInertiaImplicit 
)
protectedpure virtual

Add child's articulated inertia to parent's one. Forward dynamics routine.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addChildArtInertiaTo()

virtual void dart::dynamics::Joint::addChildArtInertiaTo ( Eigen::Matrix6d _parentArtInertia,
const Eigen::Matrix6d _childArtInertia 
)
protectedpure virtual

Add child's articulated inertia to parent's one.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addChildBiasForceForInvAugMassMatrix()

virtual void dart::dynamics::Joint::addChildBiasForceForInvAugMassMatrix ( Eigen::Vector6d _parentBiasForce,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasForce 
)
protectedpure virtual

Add child's bias force to parent's one.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addChildBiasForceForInvMassMatrix()

virtual void dart::dynamics::Joint::addChildBiasForceForInvMassMatrix ( Eigen::Vector6d _parentBiasForce,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasForce 
)
protectedpure virtual

Add child's bias force to parent's one.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addChildBiasForceTo()

virtual void dart::dynamics::Joint::addChildBiasForceTo ( Eigen::Vector6d _parentBiasForce,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasForce,
const Eigen::Vector6d _childPartialAcc 
)
protectedpure virtual

Add child's bias force to parent's one.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addChildBiasImpulseTo()

virtual void dart::dynamics::Joint::addChildBiasImpulseTo ( Eigen::Vector6d _parentBiasImpulse,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasImpulse 
)
protectedpure virtual

Add child's bias impulse to parent's one.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addInvMassMatrixSegmentTo()

virtual void dart::dynamics::Joint::addInvMassMatrixSegmentTo ( Eigen::Vector6d _acc)
protectedpure virtual

◆ addObserver()

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

Add an Observer to the list of Observers.

◆ addVelocityChangeTo()

virtual void dart::dynamics::Joint::addVelocityChangeTo ( Eigen::Vector6d _velocityChange)
protectedpure virtual

Add joint velocity change to _velocityChange.

Implemented in dart::dynamics::ZeroDofJoint.

◆ addVelocityTo()

virtual void dart::dynamics::Joint::addVelocityTo ( Eigen::Vector6d _vel)
protectedpure virtual

Add joint velocity to _vel.

Implemented in dart::dynamics::ZeroDofJoint.

◆ checkSanity()

bool dart::dynamics::Joint::checkSanity ( bool  _printWarnings = true) const

Returns false if the initial position or initial velocity are outside of limits.

◆ clone()

virtual Joint* dart::dynamics::Joint::clone ( ) const
protectedpure virtual

Create a clone of this Joint.

This may only be called by the Skeleton class.

Implemented in dart::dynamics::WeldJoint.

◆ computePotentialEnergy()

virtual double dart::dynamics::Joint::computePotentialEnergy ( ) const
pure virtual

Compute and return the potential energy.

Implemented in dart::dynamics::ZeroDofJoint.

◆ copy() [1/2]

void dart::dynamics::Joint::copy ( const Joint _otherJoint)

Copy the properties of another Joint.

◆ copy() [2/2]

void dart::dynamics::Joint::copy ( const Joint _otherJoint)

Copy the properties of another Joint.

◆ createDofPointer()

DegreeOfFreedom * dart::dynamics::Joint::createDofPointer ( std::size_t  _indexInJoint)
protected

Create a DegreeOfFreedom pointer.

Parameters
[in]_nameDegreeOfFreedom's name.
[in]_indexInJointDegreeOfFreedom's index within the joint. Note that the index should be unique within the joint.

DegreeOfFreedom should be created by the Joint because the DegreeOfFreedom class has a protected constructor, and the Joint is responsible for memory management of the pointer which is returned.

◆ createJointAspect()

template<typename ... Args>
Aspect* dart::dynamics::Joint::createJointAspect ( Args &&...  args)
inline

Construct a(an) JointAspect inside of this Composite.

◆ getAcceleration()

virtual double dart::dynamics::Joint::getAcceleration ( std::size_t  _index) const
pure virtual

Get the acceleration of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getAccelerationLowerLimit()

virtual double dart::dynamics::Joint::getAccelerationLowerLimit ( std::size_t  _index) const
pure virtual

Get lower limit for acceleration.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getAccelerationLowerLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getAccelerationLowerLimits ( ) const
pure virtual

Get the acceleration upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getAccelerations()

virtual Eigen::VectorXd dart::dynamics::Joint::getAccelerations ( ) const
pure virtual

Get the accelerations of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getAccelerationUpperLimit()

virtual double dart::dynamics::Joint::getAccelerationUpperLimit ( std::size_t  _index) const
pure virtual

Get upper limit for acceleration.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getAccelerationUpperLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getAccelerationUpperLimits ( ) const
pure virtual

Get the acceleration upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getActuatorType()

Joint::ActuatorType dart::dynamics::Joint::getActuatorType ( ) const

Get actuator type.

◆ getAspectProperties()

const AspectProperties& dart::common::EmbedProperties< Joint , detail::JointProperties >::getAspectProperties ( ) const
inlineinherited

◆ getBodyConstraintWrench()

virtual Eigen::Vector6d dart::dynamics::Joint::getBodyConstraintWrench ( ) const
pure virtual

Get constraint wrench expressed in body node frame.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getChildBodyNode() [1/2]

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

Get the child BodyNode of this Joint.

◆ getChildBodyNode() [2/2]

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

Get the (const) child BodyNode of this Joint.

◆ getCommand()

virtual double dart::dynamics::Joint::getCommand ( std::size_t  _index) const
pure virtual

Get a single command.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getCommands()

virtual Eigen::VectorXd dart::dynamics::Joint::getCommands ( ) const
pure virtual

Get all commands for this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getConstraintImpulse()

virtual double dart::dynamics::Joint::getConstraintImpulse ( std::size_t  _index) const
pure virtual

Get a single constraint impulse.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getCoulombFriction()

virtual double dart::dynamics::Joint::getCoulombFriction ( std::size_t  _index) const
pure virtual

Get joint Coulomb friction froce.

Parameters
[in]_indexIndex of joint axis.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getDampingCoefficient()

virtual double dart::dynamics::Joint::getDampingCoefficient ( std::size_t  _index) const
pure virtual

Get coefficient of joint damping (viscous friction) force.

Parameters
[in]_indexIndex of joint axis.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getDof() [1/2]

virtual const DegreeOfFreedom* dart::dynamics::Joint::getDof ( std::size_t  _index) const
pure virtual

Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getDof() [2/2]

virtual DegreeOfFreedom* dart::dynamics::Joint::getDof ( std::size_t  _index)
pure virtual

Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getDofName()

virtual const std::string& dart::dynamics::Joint::getDofName ( std::size_t  _index) const
pure virtual

◆ getForce()

virtual double dart::dynamics::Joint::getForce ( std::size_t  _index) const
pure virtual

Get the force of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getForceLowerLimit()

virtual double dart::dynamics::Joint::getForceLowerLimit ( std::size_t  _index) const
pure virtual

Get lower limit for force.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getForceLowerLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getForceLowerLimits ( ) const
pure virtual

Get the force upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getForces()

virtual Eigen::VectorXd dart::dynamics::Joint::getForces ( ) const
pure virtual

Get the forces of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getForceUpperLimit()

virtual double dart::dynamics::Joint::getForceUpperLimit ( std::size_t  _index) const
pure virtual

Get upper limit for force.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getForceUpperLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getForceUpperLimits ( ) const
pure virtual

Get the force upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getIndexInSkeleton()

virtual std::size_t dart::dynamics::Joint::getIndexInSkeleton ( std::size_t  _index) const
pure virtual

Get a unique index in skeleton of a generalized coordinate in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getIndexInTree()

virtual std::size_t dart::dynamics::Joint::getIndexInTree ( std::size_t  _index) const
pure virtual

Get a unique index in the kinematic tree of a generalized coordinate in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getInitialPosition()

virtual double dart::dynamics::Joint::getInitialPosition ( std::size_t  _index) const
pure virtual

Get the position that resetPosition() will give to this coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getInitialPositions()

virtual Eigen::VectorXd dart::dynamics::Joint::getInitialPositions ( ) const
pure virtual

Get the positions that resetPositions() will give to this Joint's coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getInitialVelocities()

virtual Eigen::VectorXd dart::dynamics::Joint::getInitialVelocities ( ) const
pure virtual

Get the velocities that resetVelocities() will give to this Joint's coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getInitialVelocity()

virtual double dart::dynamics::Joint::getInitialVelocity ( std::size_t  _index) const
pure virtual

Get the velocity that resetVelocity() will give to this coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getInvAugMassMatrixSegment()

virtual void dart::dynamics::Joint::getInvAugMassMatrixSegment ( Eigen::MatrixXd &  _invMassMat,
const std::size_t  _col,
const Eigen::Matrix6d _artInertia,
const Eigen::Vector6d _spatialAcc 
)
protectedpure virtual

◆ getInvMassMatrixSegment()

virtual void dart::dynamics::Joint::getInvMassMatrixSegment ( Eigen::MatrixXd &  _invMassMat,
const std::size_t  _col,
const Eigen::Matrix6d _artInertia,
const Eigen::Vector6d _spatialAcc 
)
protectedpure virtual

◆ getJointAspect() [1/3]

Aspect* dart::dynamics::Joint::getJointAspect ( )
inline

Get a(an) JointAspect from this Composite.

◆ getJointAspect() [2/3]

const Aspect* dart::dynamics::Joint::getJointAspect ( ) const
inline

Get a(an) JointAspect from this Composite.

◆ getJointAspect() [3/3]

Aspect* dart::dynamics::Joint::getJointAspect ( const bool  createIfNull)
inline

Get a(an) JointAspect from this Composite.

If _createIfNull is true, then a(an) JointAspect will be generated if one does not already exist.

◆ getJointIndexInSkeleton()

std::size_t dart::dynamics::Joint::getJointIndexInSkeleton ( ) const

Get the index of this Joint within its Skeleton.

◆ getJointIndexInTree()

std::size_t dart::dynamics::Joint::getJointIndexInTree ( ) const

Get the index of this Joint within its tree.

◆ getJointProperties()

const Joint::Properties & dart::dynamics::Joint::getJointProperties ( ) const

Get the Properties of this Joint.

◆ getLocalJacobian() [1/2]

const math::Jacobian dart::dynamics::Joint::getLocalJacobian ( ) const

Deprecated. Use getRelativeJacobian() instead.

◆ getLocalJacobian() [2/2]

math::Jacobian dart::dynamics::Joint::getLocalJacobian ( const Eigen::VectorXd &  positions) const

Deprecated. Use getRelativeJacobian() instead.

◆ getLocalJacobianTimeDeriv()

const math::Jacobian dart::dynamics::Joint::getLocalJacobianTimeDeriv ( ) const

Deprecated. Use getRelativeJacobianTimeDeriv() instead.

◆ getLocalPrimaryAcceleration()

const Eigen::Vector6d & dart::dynamics::Joint::getLocalPrimaryAcceleration ( ) const

Deprecated. Use getLocalPrimaryAcceleration() instead.

◆ getLocalSpatialAcceleration()

const Eigen::Vector6d & dart::dynamics::Joint::getLocalSpatialAcceleration ( ) const

Deprecated. Use getLocalSpatialAcceleration() instead.

◆ getLocalSpatialVelocity()

const Eigen::Vector6d & dart::dynamics::Joint::getLocalSpatialVelocity ( ) const

Deprecated. Use getLocalSpatialVelocity() instead.

◆ getLocalTransform()

const Eigen::Isometry3d & dart::dynamics::Joint::getLocalTransform ( ) const

Deprecated. Use getRelativeTransform() instead.

◆ getName()

const std::string & dart::dynamics::Joint::getName ( ) const

Get joint name.

◆ getNumDofs()

virtual std::size_t dart::dynamics::Joint::getNumDofs ( ) const
pure virtual

Get number of generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getParentBodyNode() [1/2]

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

Get the parent BodyNode of this Joint.

◆ getParentBodyNode() [2/2]

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

Get the (const) parent BodyNode of this Joint.

◆ getPosition()

virtual double dart::dynamics::Joint::getPosition ( std::size_t  _index) const
pure virtual

Get the position of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPositionDifferences()

virtual Eigen::VectorXd dart::dynamics::Joint::getPositionDifferences ( const Eigen::VectorXd &  _q2,
const Eigen::VectorXd &  _q1 
) const
pure virtual

Return the difference of two generalized coordinates which are measured in the configuration space of this Skeleton.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPositionLowerLimit()

virtual double dart::dynamics::Joint::getPositionLowerLimit ( std::size_t  _index) const
pure virtual

Get lower limit for position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPositionLowerLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getPositionLowerLimits ( ) const
pure virtual

Get the position lower limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPositions()

virtual Eigen::VectorXd dart::dynamics::Joint::getPositions ( ) const
pure virtual

Get the positions of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPositionUpperLimit()

virtual double dart::dynamics::Joint::getPositionUpperLimit ( std::size_t  _index) const
pure virtual

Get upper limit for position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPositionUpperLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getPositionUpperLimits ( ) const
pure virtual

Get the position upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getPotentialEnergy()

double dart::dynamics::Joint::getPotentialEnergy ( ) const

Get potential energy.

◆ getRelativeJacobian() [1/2]

virtual const math::Jacobian dart::dynamics::Joint::getRelativeJacobian ( ) const
pure virtual

Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getRelativeJacobian() [2/2]

virtual math::Jacobian dart::dynamics::Joint::getRelativeJacobian ( const Eigen::VectorXd &  positions) const
pure virtual

Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getRelativeJacobianTimeDeriv()

virtual const math::Jacobian dart::dynamics::Joint::getRelativeJacobianTimeDeriv ( ) const
pure virtual

Get time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getRelativePrimaryAcceleration()

const Eigen::Vector6d & dart::dynamics::Joint::getRelativePrimaryAcceleration ( ) const

Get J * \ddot{q} of this joint.

◆ getRelativeSpatialAcceleration()

const Eigen::Vector6d & dart::dynamics::Joint::getRelativeSpatialAcceleration ( ) const

Get spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

◆ getRelativeSpatialVelocity()

const Eigen::Vector6d & dart::dynamics::Joint::getRelativeSpatialVelocity ( ) const

Get spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

◆ getRelativeTransform()

const Eigen::Isometry3d & dart::dynamics::Joint::getRelativeTransform ( ) const

Get transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

◆ getRestPosition()

virtual double dart::dynamics::Joint::getRestPosition ( std::size_t  _index) const
pure virtual

Get rest position of spring force.

Parameters
[in]_indexIndex of joint axis.
Returns
Rest position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getSkeleton() [1/2]

SkeletonPtr dart::dynamics::Joint::getSkeleton ( )

Get the Skeleton that this Joint belongs to.

◆ getSkeleton() [2/2]

std::shared_ptr< const Skeleton > dart::dynamics::Joint::getSkeleton ( ) const

Get the (const) Skeleton that this Joint belongs to.

◆ getSpatialToGeneralized()

virtual Eigen::VectorXd dart::dynamics::Joint::getSpatialToGeneralized ( const Eigen::Vector6d _spatial)
protectedpure virtual

◆ getSpringStiffness()

virtual double dart::dynamics::Joint::getSpringStiffness ( std::size_t  _index) const
pure virtual

Get stiffness of joint spring force.

Parameters
[in]_indexIndex of joint axis.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getTransformFromChildBodyNode()

const Eigen::Isometry3d & dart::dynamics::Joint::getTransformFromChildBodyNode ( ) const

Get transformation from child body node to this joint.

◆ getTransformFromParentBodyNode()

const Eigen::Isometry3d & dart::dynamics::Joint::getTransformFromParentBodyNode ( ) const

Get transformation from parent body node to this joint.

◆ getTreeIndex()

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

Get the index of the tree that this Joint belongs to.

◆ getType()

virtual const std::string& dart::dynamics::Joint::getType ( ) const
pure virtual

Gets a string representing the joint type.

Implemented in dart::dynamics::WeldJoint.

◆ getVelocities()

virtual Eigen::VectorXd dart::dynamics::Joint::getVelocities ( ) const
pure virtual

Get the velocities of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVelocity()

virtual double dart::dynamics::Joint::getVelocity ( std::size_t  _index) const
pure virtual

Get the velocity of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVelocityChange()

virtual double dart::dynamics::Joint::getVelocityChange ( std::size_t  _index) const
pure virtual

Get a single velocity change.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVelocityLowerLimit()

virtual double dart::dynamics::Joint::getVelocityLowerLimit ( std::size_t  _index) const
pure virtual

Get lower limit for velocity.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVelocityLowerLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getVelocityLowerLimits ( ) const
pure virtual

Get the velocity lower limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVelocityUpperLimit()

virtual double dart::dynamics::Joint::getVelocityUpperLimit ( std::size_t  _index) const
pure virtual

Get upper limit for velocity.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVelocityUpperLimits()

virtual Eigen::VectorXd dart::dynamics::Joint::getVelocityUpperLimits ( ) const
pure virtual

Get the velocity upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ getVersion()

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

Get the version number of this object.

◆ hasJointAspect()

bool dart::dynamics::Joint::hasJointAspect ( ) const
inline

Check if this Composite currently has JointAspect .

◆ hasPositionLimit()

virtual bool dart::dynamics::Joint::hasPositionLimit ( std::size_t  _index) const
pure virtual

Get whether the position of a generalized coordinate has limits.

Implemented in dart::dynamics::ZeroDofJoint.

◆ incrementVersion()

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

Increment the version for this object.

◆ integratePositions()

virtual void dart::dynamics::Joint::integratePositions ( double  _dt)
pure virtual

Integrate positions using Euler method.

Implemented in dart::dynamics::ZeroDofJoint.

◆ integrateVelocities()

virtual void dart::dynamics::Joint::integrateVelocities ( double  _dt)
pure virtual

Integrate velocities using Euler method.

Implemented in dart::dynamics::ZeroDofJoint.

◆ isCyclic()

virtual bool dart::dynamics::Joint::isCyclic ( std::size_t  _index) const
pure virtual

Get whether a generalized coordinate is cyclic.

Return true if and only if this generalized coordinate has an infinite number of positions that produce the same relative transform. Note that, for a multi-DOF joint, producing a cycle may require altering the position of this Joint's other generalized coordinates.

Implemented in dart::dynamics::WeldJoint.

◆ isDofNamePreserved()

virtual bool dart::dynamics::Joint::isDofNamePreserved ( std::size_t  _index) const
pure virtual

◆ isDynamic()

bool dart::dynamics::Joint::isDynamic ( ) const

Return true if this joint is dynamic joint.

◆ isKinematic()

bool dart::dynamics::Joint::isKinematic ( ) const

Return true if this joint is kinematic joint.

Kinematic joint means the motion is prescribed by position or velocity or acceleration, which is determined by the actuator type. ACCELERATION/VELOCITY/LOCKED are kinematic joints while FORCE/PASSIVE/SERVO are dynamic joints.

◆ isPositionLimitEnforced()

bool dart::dynamics::Joint::isPositionLimitEnforced ( ) const

Get whether enforcing joint position limit.

The joint position limit is valid when the actutor type is one of PASSIVE/FORCE.

See also
ActuatorType

◆ notifyAccelerationUpdate()

void dart::dynamics::Joint::notifyAccelerationUpdate ( )

Notify that an acceleration has updated.

◆ notifyAccelerationUpdated()

void dart::dynamics::Joint::notifyAccelerationUpdated ( )

Notify that an acceleration has updated.

◆ notifyPositionUpdate()

void dart::dynamics::Joint::notifyPositionUpdate ( )

Notify that a position has updated.

◆ notifyPositionUpdated()

void dart::dynamics::Joint::notifyPositionUpdated ( )

Notify that a position has updated.

◆ notifyVelocityUpdate()

void dart::dynamics::Joint::notifyVelocityUpdate ( )

Notify that a velocity has updated.

◆ notifyVelocityUpdated()

void dart::dynamics::Joint::notifyVelocityUpdated ( )

Notify that a velocity has updated.

◆ operator=()

Joint & dart::dynamics::Joint::operator= ( const Joint _otherJoint)

◆ preserveDofName()

virtual void dart::dynamics::Joint::preserveDofName ( std::size_t  _index,
bool  _preserve 
)
pure virtual

◆ registerDofs()

virtual void dart::dynamics::Joint::registerDofs ( )
protectedpure virtual

Called by the Skeleton class.

Implemented in dart::dynamics::ZeroDofJoint.

◆ releaseJointAspect()

std::unique_ptr< Aspect > dart::dynamics::Joint::releaseJointAspect ( )
inline

Remove a(an) JointAspect from this Composite, but return its unique_ptr instead of letting it be deleted.

This allows you to safely use move semantics to transfer a(an) JointAspect between two Composites.

◆ removeJointAspect()

void dart::dynamics::Joint::removeJointAspect ( )
inline

Remove a(an) JointAspect from this Composite.

◆ removeObserver()

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

Remove an Observer from the list of Observers.

◆ resetAccelerations()

virtual void dart::dynamics::Joint::resetAccelerations ( )
pure virtual

Set the accelerations of all generalized coordinates in this Joint to zero.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetCommands()

virtual void dart::dynamics::Joint::resetCommands ( )
pure virtual

Set all the commands for this Joint to zero.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetConstraintImpulses()

virtual void dart::dynamics::Joint::resetConstraintImpulses ( )
pure virtual

Set zero all the constraint impulses.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetForces()

virtual void dart::dynamics::Joint::resetForces ( )
pure virtual

Set the forces of all generalized coordinates in this Joint to zero.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetPosition()

virtual void dart::dynamics::Joint::resetPosition ( std::size_t  _index)
pure virtual

Set the position of this generalized coordinate to its initial position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetPositions()

virtual void dart::dynamics::Joint::resetPositions ( )
pure virtual

Set the positions of all generalized coordinates in this Joint to their initial positions.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetTotalImpulses()

virtual void dart::dynamics::Joint::resetTotalImpulses ( )
protectedpure virtual

Set total impulses to zero.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetVelocities()

virtual void dart::dynamics::Joint::resetVelocities ( )
pure virtual

Set the velocities of all generalized coordinates in this Joint to their initial velocities.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetVelocity()

virtual void dart::dynamics::Joint::resetVelocity ( std::size_t  _index)
pure virtual

Set the velocity of a generalized coordinate in this Joint to its initial velocity.

Implemented in dart::dynamics::ZeroDofJoint.

◆ resetVelocityChanges()

virtual void dart::dynamics::Joint::resetVelocityChanges ( )
pure virtual

Set zero all the velocity change.

Implemented in dart::dynamics::ZeroDofJoint.

◆ 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.

◆ setAcceleration()

virtual void dart::dynamics::Joint::setAcceleration ( std::size_t  _index,
double  _acceleration 
)
pure virtual

Set the acceleration of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setAccelerationLowerLimit()

virtual void dart::dynamics::Joint::setAccelerationLowerLimit ( std::size_t  _index,
double  _acceleration 
)
pure virtual

Set lower limit for acceleration.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setAccelerationLowerLimits()

virtual void dart::dynamics::Joint::setAccelerationLowerLimits ( const Eigen::VectorXd &  lowerLimits)
pure virtual

Set the acceleration upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setAccelerations()

virtual void dart::dynamics::Joint::setAccelerations ( const Eigen::VectorXd &  _accelerations)
pure virtual

Set the accelerations of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setAccelerationUpperLimit()

virtual void dart::dynamics::Joint::setAccelerationUpperLimit ( std::size_t  _index,
double  _acceleration 
)
pure virtual

Set upper limit for acceleration.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setAccelerationUpperLimits()

virtual void dart::dynamics::Joint::setAccelerationUpperLimits ( const Eigen::VectorXd &  upperLimits)
pure virtual

Set the acceleration upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setActuatorType()

void dart::dynamics::Joint::setActuatorType ( Joint::ActuatorType  _actuatorType)

Set actuator type.

◆ setAspectProperties()

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

Set the AspectProperties of this Joint.

◆ setCommand()

virtual void dart::dynamics::Joint::setCommand ( std::size_t  _index,
double  _command 
)
pure virtual

Set a single command.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setCommands()

virtual void dart::dynamics::Joint::setCommands ( const Eigen::VectorXd &  _commands)
pure virtual

Set all commands for this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setConstraintImpulse()

virtual void dart::dynamics::Joint::setConstraintImpulse ( std::size_t  _index,
double  _impulse 
)
pure virtual

Set a single constraint impulse.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setCoulombFriction()

virtual void dart::dynamics::Joint::setCoulombFriction ( std::size_t  _index,
double  _friction 
)
pure virtual

Set joint Coulomb friction froce.

Parameters
[in]_indexIndex of joint axis.
[in]_frictionJoint Coulomb friction froce given index.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setDampingCoefficient()

virtual void dart::dynamics::Joint::setDampingCoefficient ( std::size_t  _index,
double  _coeff 
)
pure virtual

Set coefficient of joint damping (viscous friction) force.

Parameters
[in]_indexIndex of joint axis.
[in]_coeffDamping coefficient.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setDofName()

virtual const std::string& dart::dynamics::Joint::setDofName ( std::size_t  _index,
const std::string &  _name,
bool  _preserveName = true 
)
pure virtual

◆ setForce()

virtual void dart::dynamics::Joint::setForce ( std::size_t  _index,
double  _force 
)
pure virtual

Set the force of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setForceLowerLimit()

virtual void dart::dynamics::Joint::setForceLowerLimit ( std::size_t  _index,
double  _force 
)
pure virtual

Set lower limit for force.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setForceLowerLimits()

virtual void dart::dynamics::Joint::setForceLowerLimits ( const Eigen::VectorXd &  lowerLimits)
pure virtual

Set the force upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setForces()

virtual void dart::dynamics::Joint::setForces ( const Eigen::VectorXd &  _forces)
pure virtual

Set the forces of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setForceUpperLimit()

virtual void dart::dynamics::Joint::setForceUpperLimit ( std::size_t  _index,
double  _force 
)
pure virtual

Set upper limit for force.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setForceUpperLimits()

virtual void dart::dynamics::Joint::setForceUpperLimits ( const Eigen::VectorXd &  upperLimits)
pure virtual

Set the force upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setInitialPosition()

virtual void dart::dynamics::Joint::setInitialPosition ( std::size_t  _index,
double  _initial 
)
pure virtual

Change the position that resetPositions() will give to this coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setInitialPositions()

virtual void dart::dynamics::Joint::setInitialPositions ( const Eigen::VectorXd &  _initial)
pure virtual

Change the positions that resetPositions() will give to this Joint's coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setInitialVelocities()

virtual void dart::dynamics::Joint::setInitialVelocities ( const Eigen::VectorXd &  _initial)
pure virtual

Change the velocities that resetVelocities() will give to this Joint's coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setInitialVelocity()

virtual void dart::dynamics::Joint::setInitialVelocity ( std::size_t  _index,
double  _initial 
)
pure virtual

Change the velocity that resetVelocity() will give to this coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setJointAspect() [1/2]

void dart::dynamics::Joint::setJointAspect ( const Aspect aspect)
inline

Make a clone of JointAspect and place the clone into this Composite.

If a(an) JointAspect already exists in this Composite, the existing JointAspect will be destroyed.

◆ setJointAspect() [2/2]

void dart::dynamics::Joint::setJointAspect ( std::unique_ptr< Aspect > &&  aspect)
inline

Use move semantics to place JointAspect into this Composite.

If a(an) JointAspect already exists in this Composite, the existing JointAspect will be destroyed.

◆ setName()

const std::string & dart::dynamics::Joint::setName ( const std::string &  _name,
bool  _renameDofs = true 
)

Set joint name and return the name.

Parameters
[in]_renameDofsIf true, the names of the joint's degrees of freedom will be updated by calling updateDegreeOfFreedomNames().

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

◆ setPartialAccelerationTo()

virtual void dart::dynamics::Joint::setPartialAccelerationTo ( Eigen::Vector6d _partialAcceleration,
const Eigen::Vector6d _childVelocity 
)
protectedpure virtual

Set joint partial acceleration to _partialAcceleration.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setPosition()

virtual void dart::dynamics::Joint::setPosition ( std::size_t  _index,
double  _position 
)
pure virtual

Set the position of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setPositionLimitEnforced()

void dart::dynamics::Joint::setPositionLimitEnforced ( bool  _isPositionLimitEnforced)

Set to enforce joint position limit.

The joint position limit is valid when the actutor type is one of PASSIVE/FORCE.

See also
ActuatorType

◆ setPositionLowerLimit()

virtual void dart::dynamics::Joint::setPositionLowerLimit ( std::size_t  _index,
double  _position 
)
pure virtual

Set lower limit for position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setPositionLowerLimits()

virtual void dart::dynamics::Joint::setPositionLowerLimits ( const Eigen::VectorXd &  lowerLimits)
pure virtual

Set the position lower limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setPositions()

virtual void dart::dynamics::Joint::setPositions ( const Eigen::VectorXd &  _positions)
pure virtual

Set the positions of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setPositionUpperLimit()

virtual void dart::dynamics::Joint::setPositionUpperLimit ( std::size_t  _index,
double  _position 
)
pure virtual

Set upper limit for position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setPositionUpperLimits()

virtual void dart::dynamics::Joint::setPositionUpperLimits ( const Eigen::VectorXd &  upperLimits)
pure virtual

Set the position upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setProperties()

void dart::dynamics::Joint::setProperties ( const Properties properties)

Set the Properties of this Joint.

◆ setRestPosition()

virtual void dart::dynamics::Joint::setRestPosition ( std::size_t  _index,
double  _q0 
)
pure virtual

Set rest position of spring force.

Parameters
[in]_indexIndex of joint axis.
[in]_q0Rest position.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setSpringStiffness()

virtual void dart::dynamics::Joint::setSpringStiffness ( std::size_t  _index,
double  _k 
)
pure virtual

Set stiffness of joint spring force.

Parameters
[in]_indexIndex of joint axis.
[in]_kSpring stiffness.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setTransformFromChildBodyNode()

void dart::dynamics::Joint::setTransformFromChildBodyNode ( const Eigen::Isometry3d &  _T)
virtual

Set transformation from child body node to this joint.

Reimplemented in dart::dynamics::WeldJoint.

◆ setTransformFromParentBodyNode()

void dart::dynamics::Joint::setTransformFromParentBodyNode ( const Eigen::Isometry3d &  _T)
virtual

Set transformation from parent body node to this joint.

Reimplemented in dart::dynamics::WeldJoint.

◆ setVelocities()

virtual void dart::dynamics::Joint::setVelocities ( const Eigen::VectorXd &  _velocities)
pure virtual

Set the velocities of all generalized coordinates in this Joint.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVelocity()

virtual void dart::dynamics::Joint::setVelocity ( std::size_t  _index,
double  _velocity 
)
pure virtual

Set the velocity of a single generalized coordinate.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVelocityChange()

virtual void dart::dynamics::Joint::setVelocityChange ( std::size_t  _index,
double  _velocityChange 
)
pure virtual

Set a single velocity change.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVelocityLowerLimit()

virtual void dart::dynamics::Joint::setVelocityLowerLimit ( std::size_t  _index,
double  _velocity 
)
pure virtual

Set lower limit for velocity.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVelocityLowerLimits()

virtual void dart::dynamics::Joint::setVelocityLowerLimits ( const Eigen::VectorXd &  lowerLimits)
pure virtual

Set the velocity lower limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVelocityUpperLimit()

virtual void dart::dynamics::Joint::setVelocityUpperLimit ( std::size_t  _index,
double  _velocity 
)
pure virtual

Set upper limit for velocity.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVelocityUpperLimits()

virtual void dart::dynamics::Joint::setVelocityUpperLimits ( const Eigen::VectorXd &  upperLimits)
pure virtual

Set the velocity upper limits of all the generalized coordinates.

Implemented in dart::dynamics::ZeroDofJoint.

◆ setVersionDependentObject()

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

◆ updateAcceleration()

virtual void dart::dynamics::Joint::updateAcceleration ( const Eigen::Matrix6d _artInertia,
const Eigen::Vector6d _spatialAcc 
)
protectedpure virtual

Update joint acceleration.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateArticulatedInertia()

void dart::dynamics::Joint::updateArticulatedInertia ( ) const
protected

Tells the Skeleton to update the articulated inertia if it needs updating.

◆ updateConstrainedTerms()

virtual void dart::dynamics::Joint::updateConstrainedTerms ( double  _timeStep)
protectedpure virtual

Update constrained terms for forward dynamics.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateDegreeOfFreedomNames()

virtual void dart::dynamics::Joint::updateDegreeOfFreedomNames ( )
protectedpure virtual

Update the names of the joint's degrees of freedom.

Used when setName() is called with _renameDofs set to true.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateForceFD()

virtual void dart::dynamics::Joint::updateForceFD ( const Eigen::Vector6d _bodyForce,
double  _timeStep,
bool  _withDampingForcese,
bool  _withSpringForces 
)
protectedpure virtual

Update joint force for forward dynamics.

Parameters
[in]_bodyForceTransmitting spatial body force from the parent BodyNode to the child BodyNode. The spatial force is expressed in the child BodyNode's frame.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateForceID()

virtual void dart::dynamics::Joint::updateForceID ( const Eigen::Vector6d _bodyForce,
double  _timeStep,
bool  _withDampingForces,
bool  _withSpringForces 
)
protectedpure virtual

Update joint force for inverse dynamics.

Parameters
[in]_bodyForceTransmitting spatial body force from the parent BodyNode to the child BodyNode. The spatial force is expressed in the child BodyNode's frame.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateImpulseFD()

virtual void dart::dynamics::Joint::updateImpulseFD ( const Eigen::Vector6d _bodyImpulse)
protectedpure virtual

Update joint impulses for forward dynamics.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateImpulseID()

virtual void dart::dynamics::Joint::updateImpulseID ( const Eigen::Vector6d _bodyImpulse)
protectedpure virtual

Update joint impulses for inverse dynamics.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateInvProjArtInertia()

virtual void dart::dynamics::Joint::updateInvProjArtInertia ( const Eigen::Matrix6d _artInertia)
protectedpure virtual

Update inverse of projected articulated body inertia.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateInvProjArtInertiaImplicit()

virtual void dart::dynamics::Joint::updateInvProjArtInertiaImplicit ( const Eigen::Matrix6d _artInertia,
double  _timeStep 
)
protectedpure virtual

Forward dynamics routine.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateLocalJacobian()

void dart::dynamics::Joint::updateLocalJacobian ( bool  mandatory = true) const
protected

Deprecated. Use updateRelativeJacobian() instead.

◆ updateLocalJacobianTimeDeriv()

void dart::dynamics::Joint::updateLocalJacobianTimeDeriv ( ) const
protected

Deprecated. Use updateRelativeJacobianTimeDeriv() instead.

◆ updateLocalPrimaryAcceleration()

void dart::dynamics::Joint::updateLocalPrimaryAcceleration ( ) const
protected

Deprecated. Use updateRelativePrimaryAcceleration() instead.

◆ updateLocalSpatialAcceleration()

void dart::dynamics::Joint::updateLocalSpatialAcceleration ( ) const
protected

Deprecated. Use updateRelativeSpatialAcceleration() instead.

◆ updateLocalSpatialVelocity()

void dart::dynamics::Joint::updateLocalSpatialVelocity ( ) const
protected

Deprecated. Use updateRelativeSpatialVelocity() instead.

◆ updateLocalTransform()

void dart::dynamics::Joint::updateLocalTransform ( ) const
protected

Deprecated. Use updateRelativeTransform() instead.

◆ updateRelativeJacobian()

virtual void dart::dynamics::Joint::updateRelativeJacobian ( bool  mandatory = true) const
protectedpure virtual

Update spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Parameters
[in]mandatoryThis argument can be set to false if the Jacobian update request is due to a change in Joint positions, because not all Joint types have a relative Jacobian that depends on their Joint positions, so a relative Jacobian update would not actually be required.

Implemented in dart::dynamics::WeldJoint.

◆ updateRelativeJacobianTimeDeriv()

virtual void dart::dynamics::Joint::updateRelativeJacobianTimeDeriv ( ) const
protectedpure virtual

Update time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

If the relative Jacobian time derivative of this Joint is zero, then this function will be a no op.

Implemented in dart::dynamics::WeldJoint.

◆ updateRelativePrimaryAcceleration()

virtual void dart::dynamics::Joint::updateRelativePrimaryAcceleration ( ) const
protectedpure virtual

Update J * \ddot{q} of this joint.

Implemented in dart::dynamics::WeldJoint.

◆ updateRelativeSpatialAcceleration()

virtual void dart::dynamics::Joint::updateRelativeSpatialAcceleration ( ) const
protectedpure virtual

Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Implemented in dart::dynamics::WeldJoint.

◆ updateRelativeSpatialVelocity()

virtual void dart::dynamics::Joint::updateRelativeSpatialVelocity ( ) const
protectedpure virtual

Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Implemented in dart::dynamics::WeldJoint.

◆ updateRelativeTransform()

virtual void dart::dynamics::Joint::updateRelativeTransform ( ) const
protectedpure virtual

Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Implemented in dart::dynamics::WeldJoint.

◆ updateTotalForce()

virtual void dart::dynamics::Joint::updateTotalForce ( const Eigen::Vector6d _bodyForce,
double  _timeStep 
)
protectedpure virtual

Update joint total force.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateTotalForceForInvMassMatrix()

virtual void dart::dynamics::Joint::updateTotalForceForInvMassMatrix ( const Eigen::Vector6d _bodyForce)
protectedpure virtual

◆ updateTotalImpulse()

virtual void dart::dynamics::Joint::updateTotalImpulse ( const Eigen::Vector6d _bodyImpulse)
protectedpure virtual

Update joint total impulse.

Implemented in dart::dynamics::ZeroDofJoint.

◆ updateVelocityChange()

virtual void dart::dynamics::Joint::updateVelocityChange ( const Eigen::Matrix6d _artInertia,
const Eigen::Vector6d _velocityChange 
)
protectedpure virtual

Update joint velocity change.

Parameters
_artInertia
_velocityChange

Implemented in dart::dynamics::ZeroDofJoint.

Friends And Related Function Documentation

◆ BodyNode

friend class BodyNode
friend

◆ Skeleton

friend class Skeleton
friend

◆ SoftBodyNode

friend class SoftBodyNode
friend

Member Data Documentation

◆ ACCELERATION

constexpr Joint::ActuatorType dart::dynamics::Joint::ACCELERATION = detail::ACCELERATION
staticconstexpr

◆ DefaultActuatorType

const Joint::ActuatorType dart::dynamics::Joint::DefaultActuatorType = detail::DefaultActuatorType
static

Default actuator type.

◆ FORCE

constexpr Joint::ActuatorType dart::dynamics::Joint::FORCE = detail::FORCE
staticconstexpr

◆ LOCKED

constexpr Joint::ActuatorType dart::dynamics::Joint::LOCKED = detail::LOCKED
staticconstexpr

◆ mAspectProperties

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

◆ mChildBodyNode

BodyNode* dart::dynamics::Joint::mChildBodyNode
protected

Child BodyNode pointer that this Joint belongs to.

◆ mDependent

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

◆ mIsRelativeJacobianDirty

bool dart::dynamics::Joint::mIsRelativeJacobianDirty
mutableprotected

True iff this joint's relative Jacobian has not been updated since the last position change.

◆ mIsRelativeJacobianTimeDerivDirty

bool dart::dynamics::Joint::mIsRelativeJacobianTimeDerivDirty
mutableprotected

True iff this joint's relative Jacobian time derivative has not been updated since the last position or velocity change.

◆ mNeedPrimaryAccelerationUpdate

bool dart::dynamics::Joint::mNeedPrimaryAccelerationUpdate
mutableprotected

True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativePrimaryAcceleration()

◆ mNeedSpatialAccelerationUpdate

bool dart::dynamics::Joint::mNeedSpatialAccelerationUpdate
mutableprotected

True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativeSpatialAcceleration()

◆ mNeedSpatialVelocityUpdate

bool dart::dynamics::Joint::mNeedSpatialVelocityUpdate
mutableprotected

True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVelocity()

◆ mNeedTransformUpdate

bool dart::dynamics::Joint::mNeedTransformUpdate
mutableprotected

True iff this joint's position has changed since the last call to getRelativeTransform()

◆ mObservers

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

List of current Observers.

◆ mPrimaryAcceleration

Eigen::Vector6d dart::dynamics::Joint::mPrimaryAcceleration
mutableprotected

J * q_dd.

Do not use directly! Use getRelativePrimaryAcceleration() to access this

◆ mSpatialAcceleration

Eigen::Vector6d dart::dynamics::Joint::mSpatialAcceleration
mutableprotected

Relative spatial acceleration from parent BodyNode to child BodyNode where the acceleration is expressed in the child body Frame.

Do not use directly! Use getRelativeSpatialAcceleration() to access this

◆ mSpatialVelocity

Eigen::Vector6d dart::dynamics::Joint::mSpatialVelocity
mutableprotected

Relative spatial velocity from parent BodyNode to child BodyNode where the velocity is expressed in child body Frame.

Do not use directly! Use getRelativeSpatialVelocity() to access this

◆ mT

Eigen::Isometry3d dart::dynamics::Joint::mT
mutableprotected

Relative transformation of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.

Do not use directly! Use getRelativeTransform() to access this

◆ mVersion

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

◆ PASSIVE

constexpr Joint::ActuatorType dart::dynamics::Joint::PASSIVE = detail::PASSIVE
staticconstexpr

◆ SERVO

constexpr Joint::ActuatorType dart::dynamics::Joint::SERVO = detail::SERVO
staticconstexpr

◆ VELOCITY

constexpr Joint::ActuatorType dart::dynamics::Joint::VELOCITY = detail::VELOCITY
staticconstexpr