DART  6.6.2
dart::dynamics::ZeroDofJoint Class Referenceabstract

class ZeroDofJoint More...

#include <ZeroDofJoint.hpp>

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

Classes

struct  Properties
 

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

 ZeroDofJoint (const ZeroDofJoint &)=delete
 
virtual ~ZeroDofJoint ()
 Destructor. More...
 
Properties getZeroDofJointProperties () const
 Get the Properties of this ZeroDofJoint. More...
 
DegreeOfFreedomgetDof (std::size_t) override
 Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint. More...
 
const DegreeOfFreedomgetDof (std::size_t) const override
 Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint. More...
 
const std::string & setDofName (std::size_t, const std::string &, bool) override
 Alternative to DegreeOfFreedom::setName() More...
 
void preserveDofName (std::size_t, bool) override
 Alternative to DegreeOfFreedom::preserveName() More...
 
bool isDofNamePreserved (std::size_t) const override
 Alternative to DegreeOfFreedom::isNamePreserved() More...
 
const std::string & getDofName (std::size_t) const override
 Alternative to DegreeOfFreedom::getName() More...
 
std::size_t getNumDofs () const override
 Get number of generalized coordinates. More...
 
std::size_t getIndexInSkeleton (std::size_t _index) const override
 Get a unique index in skeleton of a generalized coordinate in this Joint. More...
 
std::size_t getIndexInTree (std::size_t _index) const override
 Get a unique index in the kinematic tree of a generalized coordinate in this Joint. More...
 
void setCommand (std::size_t _index, double _command) override
 Set a single command. More...
 
double getCommand (std::size_t _index) const override
 Get a single command. More...
 
void setCommands (const Eigen::VectorXd &_commands) override
 Set all commands for this Joint. More...
 
Eigen::VectorXd getCommands () const override
 Get all commands for this Joint. More...
 
void resetCommands () override
 Set all the commands for this Joint to zero. More...
 
void setPosition (std::size_t, double) override
 Set the position of a single generalized coordinate. More...
 
double getPosition (std::size_t _index) const override
 Get the position of a single generalized coordinate. More...
 
void setPositions (const Eigen::VectorXd &_positions) override
 Set the positions of all generalized coordinates in this Joint. More...
 
Eigen::VectorXd getPositions () const override
 Get the positions of all generalized coordinates in this Joint. More...
 
void setPositionLowerLimit (std::size_t _index, double _position) override
 Set lower limit for position. More...
 
double getPositionLowerLimit (std::size_t _index) const override
 Get lower limit for position. More...
 
void setPositionLowerLimits (const Eigen::VectorXd &lowerLimits) override
 Set the position lower limits of all the generalized coordinates. More...
 
Eigen::VectorXd getPositionLowerLimits () const override
 Get the position lower limits of all the generalized coordinates. More...
 
void setPositionUpperLimit (std::size_t index, double position) override
 Set upper limit for position. More...
 
double getPositionUpperLimit (std::size_t index) const override
 Get upper limit for position. More...
 
void setPositionUpperLimits (const Eigen::VectorXd &upperLimits) override
 Set the position upper limits of all the generalized coordinates. More...
 
Eigen::VectorXd getPositionUpperLimits () const override
 Get the position upper limits of all the generalized coordinates. More...
 
bool hasPositionLimit (std::size_t _index) const override
 Get whether the position of a generalized coordinate has limits. More...
 
void resetPosition (std::size_t _index) override
 Set the position of this generalized coordinate to its initial position. More...
 
void resetPositions () override
 Set the positions of all generalized coordinates in this Joint to their initial positions. More...
 
void setInitialPosition (std::size_t _index, double _initial) override
 Change the position that resetPositions() will give to this coordinate. More...
 
double getInitialPosition (std::size_t _index) const override
 Get the position that resetPosition() will give to this coordinate. More...
 
void setInitialPositions (const Eigen::VectorXd &_initial) override
 Change the positions that resetPositions() will give to this Joint's coordinates. More...
 
Eigen::VectorXd getInitialPositions () const override
 Get the positions that resetPositions() will give to this Joint's coordinates. More...
 
void setVelocity (std::size_t _index, double _velocity) override
 Set the velocity of a single generalized coordinate. More...
 
double getVelocity (std::size_t _index) const override
 Get the velocity of a single generalized coordinate. More...
 
void setVelocities (const Eigen::VectorXd &_velocities) override
 Set the velocities of all generalized coordinates in this Joint. More...
 
Eigen::VectorXd getVelocities () const override
 Get the velocities of all generalized coordinates in this Joint. More...
 
void setVelocityLowerLimit (std::size_t _index, double _velocity) override
 Set lower limit for velocity. More...
 
double getVelocityLowerLimit (std::size_t _index) const override
 Get lower limit for velocity. More...
 
void setVelocityLowerLimits (const Eigen::VectorXd &lowerLimits) override
 Set the velocity lower limits of all the generalized coordinates. More...
 
Eigen::VectorXd getVelocityLowerLimits () const override
 Get the velocity lower limits of all the generalized coordinates. More...
 
void setVelocityUpperLimit (std::size_t _index, double _velocity) override
 Set upper limit for velocity. More...
 
double getVelocityUpperLimit (std::size_t _index) const override
 Get upper limit for velocity. More...
 
void setVelocityUpperLimits (const Eigen::VectorXd &upperLimits) override
 Set the velocity upper limits of all the generalized coordinates. More...
 
Eigen::VectorXd getVelocityUpperLimits () const override
 Get the velocity upper limits of all the generalized coordinates. More...
 
void resetVelocity (std::size_t _index) override
 Set the velocity of a generalized coordinate in this Joint to its initial velocity. More...
 
void resetVelocities () override
 Set the velocities of all generalized coordinates in this Joint to their initial velocities. More...
 
void setInitialVelocity (std::size_t _index, double _initial) override
 Change the velocity that resetVelocity() will give to this coordinate. More...
 
double getInitialVelocity (std::size_t _index) const override
 Get the velocity that resetVelocity() will give to this coordinate. More...
 
void setInitialVelocities (const Eigen::VectorXd &_initial) override
 Change the velocities that resetVelocities() will give to this Joint's coordinates. More...
 
Eigen::VectorXd getInitialVelocities () const override
 Get the velocities that resetVelocities() will give to this Joint's coordinates. More...
 
void setAcceleration (std::size_t _index, double _acceleration) override
 Set the acceleration of a single generalized coordinate. More...
 
double getAcceleration (std::size_t _index) const override
 Get the acceleration of a single generalized coordinate. More...
 
void setAccelerations (const Eigen::VectorXd &_accelerations) override
 Set the accelerations of all generalized coordinates in this Joint. More...
 
Eigen::VectorXd getAccelerations () const override
 Get the accelerations of all generalized coordinates in this Joint. More...
 
void resetAccelerations () override
 Set the accelerations of all generalized coordinates in this Joint to zero. More...
 
void setAccelerationLowerLimit (std::size_t _index, double _acceleration) override
 Set lower limit for acceleration. More...
 
double getAccelerationLowerLimit (std::size_t _index) const override
 Get lower limit for acceleration. More...
 
void setAccelerationLowerLimits (const Eigen::VectorXd &lowerLimits) override
 Set the acceleration upper limits of all the generalized coordinates. More...
 
Eigen::VectorXd getAccelerationLowerLimits () const override
 Get the acceleration upper limits of all the generalized coordinates. More...
 
void setAccelerationUpperLimit (std::size_t _index, double _acceleration) override
 Set upper limit for acceleration. More...
 
double getAccelerationUpperLimit (std::size_t _index) const override
 Get upper limit for acceleration. More...
 
void setAccelerationUpperLimits (const Eigen::VectorXd &upperLimits) override
 Set the acceleration upper limits of all the generalized coordinates. More...
 
Eigen::VectorXd getAccelerationUpperLimits () const override
 Get the acceleration upper limits of all the generalized coordinates. More...
 
void setForce (std::size_t _index, double _force) override
 Set the force of a single generalized coordinate. More...
 
double getForce (std::size_t _index) const override
 Get the force of a single generalized coordinate. More...
 
void setForces (const Eigen::VectorXd &_forces) override
 Set the forces of all generalized coordinates in this Joint. More...
 
Eigen::VectorXd getForces () const override
 Get the forces of all generalized coordinates in this Joint. More...
 
void resetForces () override
 Set the forces of all generalized coordinates in this Joint to zero. More...
 
void setForceLowerLimit (std::size_t _index, double _force) override
 Set lower limit for force. More...
 
double getForceLowerLimit (std::size_t _index) const override
 Get lower limit for force. More...
 
void setForceLowerLimits (const Eigen::VectorXd &lowerLimits) override
 Set the force upper limits of all the generalized coordinates. More...
 
Eigen::VectorXd getForceLowerLimits () const override
 Get the force upper limits of all the generalized coordinates. More...
 
void setForceUpperLimit (std::size_t _index, double _force) override
 Set upper limit for force. More...
 
double getForceUpperLimit (std::size_t _index) const override
 Get upper limit for force. More...
 
void setForceUpperLimits (const Eigen::VectorXd &upperLimits) override
 Set the force upper limits of all the generalized coordinates. More...
 
Eigen::VectorXd getForceUpperLimits () const override
 Get the force upper limits of all the generalized coordinates. More...
 
void setVelocityChange (std::size_t _index, double _velocityChange) override
 Set a single velocity change. More...
 
double getVelocityChange (std::size_t _index) const override
 Get a single velocity change. More...
 
void resetVelocityChanges () override
 Set zero all the velocity change. More...
 
void setConstraintImpulse (std::size_t _index, double _impulse) override
 Set a single constraint impulse. More...
 
double getConstraintImpulse (std::size_t _index) const override
 Get a single constraint impulse. More...
 
void resetConstraintImpulses () override
 Set zero all the constraint impulses. More...
 
void integratePositions (double _dt) override
 Integrate positions using Euler method. More...
 
void integrateVelocities (double _dt) override
 Integrate velocities using Euler method. More...
 
Eigen::VectorXd getPositionDifferences (const Eigen::VectorXd &_q2, const Eigen::VectorXd &_q1) const override
 Return the difference of two generalized coordinates which are measured in the configuration space of this Skeleton. More...
 
double computePotentialEnergy () const override
 Compute and return the potential energy. More...
 
Eigen::Vector6d getBodyConstraintWrench () const override
 Get constraint wrench expressed in body node frame. More...
 
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...
 
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...
 
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...
 
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...
 
double getPotentialEnergy () const
 Get 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 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
 
Passive forces - spring, viscous friction, Coulomb friction
void setSpringStiffness (std::size_t _index, double _k) override
 Set stiffness of joint spring force. More...
 
double getSpringStiffness (std::size_t _index) const override
 Get stiffness of joint spring force. More...
 
void setRestPosition (std::size_t _index, double _q0) override
 Set rest position of spring force. More...
 
double getRestPosition (std::size_t _index) const override
 Get rest position of spring force. More...
 
void setDampingCoefficient (std::size_t _index, double _d) override
 Set coefficient of joint damping (viscous friction) force. More...
 
double getDampingCoefficient (std::size_t _index) const override
 Get coefficient of joint damping (viscous friction) force. More...
 
void setCoulombFriction (std::size_t _index, double _friction) override
 Set joint Coulomb friction froce. More...
 
double getCoulombFriction (std::size_t _index) const override
 Get joint Coulomb friction froce. More...
 
Position
virtual bool isCyclic (std::size_t _index) const =0
 Get whether a generalized coordinate is cyclic. More...
 
Sanity Check
bool checkSanity (bool _printWarnings=true) const
 Returns false if the initial position or initial velocity are outside of limits. 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

 ZeroDofJoint ()
 Constructor called by inheriting classes. More...
 
void registerDofs () override
 Called by the Skeleton class. More...
 
void updateDegreeOfFreedomNames () override
 Update the names of the joint's degrees of freedom. More...
 
virtual Jointclone () const =0
 Create a clone of this Joint. More...
 
DegreeOfFreedomcreateDofPointer (std::size_t _indexInJoint)
 Create a DegreeOfFreedom pointer. 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
const math::Jacobian getRelativeJacobian () const override
 Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
math::Jacobian getRelativeJacobian (const Eigen::VectorXd &_positions) const override
 Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
const math::Jacobian getRelativeJacobianTimeDeriv () const override
 Get time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. More...
 
void addVelocityTo (Eigen::Vector6d &_vel) override
 Add joint velocity to _vel. More...
 
void setPartialAccelerationTo (Eigen::Vector6d &_partialAcceleration, const Eigen::Vector6d &_childVelocity) override
 Set joint partial acceleration to _partialAcceleration. More...
 
void addAccelerationTo (Eigen::Vector6d &_acc) override
 Add joint acceleration to _acc. More...
 
void addVelocityChangeTo (Eigen::Vector6d &_velocityChange) override
 Add joint velocity change to _velocityChange. More...
 
void addChildArtInertiaTo (Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia) override
 Add child's articulated inertia to parent's one. More...
 
void addChildArtInertiaImplicitTo (Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia) override
 Add child's articulated inertia to parent's one. Forward dynamics routine. More...
 
void updateInvProjArtInertia (const Eigen::Matrix6d &_artInertia) override
 Update inverse of projected articulated body inertia. More...
 
void updateInvProjArtInertiaImplicit (const Eigen::Matrix6d &_artInertia, double _timeStep) override
 Forward dynamics routine. More...
 
void addChildBiasForceTo (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce, const Eigen::Vector6d &_childPartialAcc) override
 Add child's bias force to parent's one. More...
 
void addChildBiasImpulseTo (Eigen::Vector6d &_parentBiasImpulse, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasImpulse) override
 Add child's bias impulse to parent's one. More...
 
void updateTotalForce (const Eigen::Vector6d &_bodyForce, double _timeStep) override
 Update joint total force. More...
 
void updateTotalImpulse (const Eigen::Vector6d &_bodyImpulse) override
 Update joint total impulse. More...
 
void resetTotalImpulses () override
 Set total impulses to zero. More...
 
void updateAcceleration (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc) override
 Update joint acceleration. More...
 
void updateVelocityChange (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_velocityChange) override
 Update joint velocity change. More...
 
void updateForceID (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override
 Update joint force for inverse dynamics. More...
 
void updateForceFD (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override
 Update joint force for forward dynamics. More...
 
void updateImpulseID (const Eigen::Vector6d &_bodyImpulse) override
 Update joint impulses for inverse dynamics. More...
 
void updateImpulseFD (const Eigen::Vector6d &_bodyImpulse) override
 Update joint impulses for forward dynamics. More...
 
void updateConstrainedTerms (double _timeStep) override
 Update constrained terms for forward dynamics. More...
 
Recursive algorithm routines for equations of motion
void addChildBiasForceForInvMassMatrix (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce) override
 Add child's bias force to parent's one. More...
 
void addChildBiasForceForInvAugMassMatrix (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce) override
 Add child's bias force to parent's one. More...
 
void updateTotalForceForInvMassMatrix (const Eigen::Vector6d &_bodyForce) override
 
void getInvMassMatrixSegment (Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc) override
 
void getInvAugMassMatrixSegment (Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc) override
 
void addInvMassMatrixSegmentTo (Eigen::Vector6d &_acc) override
 
Eigen::VectorXd getSpatialToGeneralized (const Eigen::Vector6d &_spatial) override
 
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...
 

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

const std::string emptyString
 Used by getDofName() More...
 
VersionCountermDependent
 

Detailed Description

Member Typedef Documentation

◆ ActuatorType

◆ Aspect

◆ AspectProperties

◆ AspectPropertiesData

◆ Base

◆ CompositeProperties

◆ Derived

◆ Properties

Constructor & Destructor Documentation

◆ ZeroDofJoint() [1/2]

dart::dynamics::ZeroDofJoint::ZeroDofJoint ( const ZeroDofJoint )
delete

◆ ~ZeroDofJoint()

dart::dynamics::ZeroDofJoint::~ZeroDofJoint ( )
virtual

Destructor.

◆ ZeroDofJoint() [2/2]

dart::dynamics::ZeroDofJoint::ZeroDofJoint ( )
protected

Constructor called by inheriting classes.

Member Function Documentation

◆ addAccelerationTo()

void dart::dynamics::ZeroDofJoint::addAccelerationTo ( Eigen::Vector6d _acc)
overrideprotectedvirtual

Add joint acceleration to _acc.

Implements dart::dynamics::Joint.

◆ addChildArtInertiaImplicitTo()

void dart::dynamics::ZeroDofJoint::addChildArtInertiaImplicitTo ( Eigen::Matrix6d _parentArtInertiaImplicit,
const Eigen::Matrix6d _childArtInertiaImplicit 
)
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ addChildArtInertiaTo()

void dart::dynamics::ZeroDofJoint::addChildArtInertiaTo ( Eigen::Matrix6d _parentArtInertia,
const Eigen::Matrix6d _childArtInertia 
)
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ addChildBiasForceForInvAugMassMatrix()

void dart::dynamics::ZeroDofJoint::addChildBiasForceForInvAugMassMatrix ( Eigen::Vector6d _parentBiasForce,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasForce 
)
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ addChildBiasForceForInvMassMatrix()

void dart::dynamics::ZeroDofJoint::addChildBiasForceForInvMassMatrix ( Eigen::Vector6d _parentBiasForce,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasForce 
)
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ addChildBiasForceTo()

void dart::dynamics::ZeroDofJoint::addChildBiasForceTo ( Eigen::Vector6d _parentBiasForce,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasForce,
const Eigen::Vector6d _childPartialAcc 
)
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ addChildBiasImpulseTo()

void dart::dynamics::ZeroDofJoint::addChildBiasImpulseTo ( Eigen::Vector6d _parentBiasImpulse,
const Eigen::Matrix6d _childArtInertia,
const Eigen::Vector6d _childBiasImpulse 
)
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ addInvMassMatrixSegmentTo()

void dart::dynamics::ZeroDofJoint::addInvMassMatrixSegmentTo ( Eigen::Vector6d _acc)
overrideprotectedvirtual

Implements dart::dynamics::Joint.

◆ addObserver()

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

Add an Observer to the list of Observers.

◆ addVelocityChangeTo()

void dart::dynamics::ZeroDofJoint::addVelocityChangeTo ( Eigen::Vector6d _velocityChange)
overrideprotectedvirtual

Add joint velocity change to _velocityChange.

Implements dart::dynamics::Joint.

◆ addVelocityTo()

void dart::dynamics::ZeroDofJoint::addVelocityTo ( Eigen::Vector6d _vel)
overrideprotectedvirtual

Add joint velocity to _vel.

Implements dart::dynamics::Joint.

◆ checkSanity()

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

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

◆ clone()

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

Create a clone of this Joint.

This may only be called by the Skeleton class.

Implemented in dart::dynamics::WeldJoint.

◆ computePotentialEnergy()

double dart::dynamics::ZeroDofJoint::computePotentialEnergy ( ) const
overridevirtual

Compute and return the potential energy.

Implements dart::dynamics::Joint.

◆ copy() [1/2]

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

Copy the properties of another Joint.

◆ copy() [2/2]

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

Copy the properties of another Joint.

◆ createDofPointer()

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

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)
inlineinherited

Construct a(an) JointAspect inside of this Composite.

◆ getAcceleration()

double dart::dynamics::ZeroDofJoint::getAcceleration ( std::size_t  _index) const
overridevirtual

Get the acceleration of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ getAccelerationLowerLimit()

double dart::dynamics::ZeroDofJoint::getAccelerationLowerLimit ( std::size_t  _index) const
overridevirtual

Get lower limit for acceleration.

Implements dart::dynamics::Joint.

◆ getAccelerationLowerLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getAccelerationLowerLimits ( ) const
overridevirtual

Get the acceleration upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getAccelerations()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getAccelerations ( ) const
overridevirtual

Get the accelerations of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ getAccelerationUpperLimit()

double dart::dynamics::ZeroDofJoint::getAccelerationUpperLimit ( std::size_t  _index) const
overridevirtual

Get upper limit for acceleration.

Implements dart::dynamics::Joint.

◆ getAccelerationUpperLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getAccelerationUpperLimits ( ) const
overridevirtual

Get the acceleration upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getActuatorType()

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

Get actuator type.

◆ getAspectProperties()

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

◆ getBodyConstraintWrench()

Eigen::Vector6d dart::dynamics::ZeroDofJoint::getBodyConstraintWrench ( ) const
overridevirtual

Get constraint wrench expressed in body node frame.

Implements dart::dynamics::Joint.

◆ getChildBodyNode() [1/2]

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

Get the child BodyNode of this Joint.

◆ getChildBodyNode() [2/2]

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

Get the (const) child BodyNode of this Joint.

◆ getCommand()

double dart::dynamics::ZeroDofJoint::getCommand ( std::size_t  _index) const
overridevirtual

Get a single command.

Implements dart::dynamics::Joint.

◆ getCommands()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getCommands ( ) const
overridevirtual

Get all commands for this Joint.

Implements dart::dynamics::Joint.

◆ getConstraintImpulse()

double dart::dynamics::ZeroDofJoint::getConstraintImpulse ( std::size_t  _index) const
overridevirtual

Get a single constraint impulse.

Implements dart::dynamics::Joint.

◆ getCoulombFriction()

double dart::dynamics::ZeroDofJoint::getCoulombFriction ( std::size_t  _index) const
overridevirtual

Get joint Coulomb friction froce.

Parameters
[in]_indexIndex of joint axis.

Implements dart::dynamics::Joint.

◆ getDampingCoefficient()

double dart::dynamics::ZeroDofJoint::getDampingCoefficient ( std::size_t  _index) const
overridevirtual

Get coefficient of joint damping (viscous friction) force.

Parameters
[in]_indexIndex of joint axis.

Implements dart::dynamics::Joint.

◆ getDof() [1/2]

const DegreeOfFreedom * dart::dynamics::ZeroDofJoint::getDof ( std::size_t  _index) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getDof() [2/2]

DegreeOfFreedom * dart::dynamics::ZeroDofJoint::getDof ( std::size_t  _index)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getDofName()

const std::string & dart::dynamics::ZeroDofJoint::getDofName ( std::size_t  _index) const
overridevirtual

◆ getForce()

double dart::dynamics::ZeroDofJoint::getForce ( std::size_t  _index) const
overridevirtual

Get the force of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ getForceLowerLimit()

double dart::dynamics::ZeroDofJoint::getForceLowerLimit ( std::size_t  _index) const
overridevirtual

Get lower limit for force.

Implements dart::dynamics::Joint.

◆ getForceLowerLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getForceLowerLimits ( ) const
overridevirtual

Get the force upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getForces()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getForces ( ) const
overridevirtual

Get the forces of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ getForceUpperLimit()

double dart::dynamics::ZeroDofJoint::getForceUpperLimit ( std::size_t  _index) const
overridevirtual

Get upper limit for force.

Implements dart::dynamics::Joint.

◆ getForceUpperLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getForceUpperLimits ( ) const
overridevirtual

Get the force upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getIndexInSkeleton()

std::size_t dart::dynamics::ZeroDofJoint::getIndexInSkeleton ( std::size_t  _index) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getIndexInTree()

std::size_t dart::dynamics::ZeroDofJoint::getIndexInTree ( std::size_t  _index) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getInitialPosition()

double dart::dynamics::ZeroDofJoint::getInitialPosition ( std::size_t  _index) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getInitialPositions()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getInitialPositions ( ) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getInitialVelocities()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getInitialVelocities ( ) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getInitialVelocity()

double dart::dynamics::ZeroDofJoint::getInitialVelocity ( std::size_t  _index) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getInvAugMassMatrixSegment()

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

Implements dart::dynamics::Joint.

◆ getInvMassMatrixSegment()

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

Implements dart::dynamics::Joint.

◆ getJointAspect() [1/3]

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

Get a(an) JointAspect from this Composite.

◆ getJointAspect() [2/3]

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

Get a(an) JointAspect from this Composite.

◆ getJointAspect() [3/3]

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

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
inherited

Get the index of this Joint within its Skeleton.

◆ getJointIndexInTree()

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

Get the index of this Joint within its tree.

◆ getJointProperties()

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

Get the Properties of this Joint.

◆ getLocalJacobian() [1/2]

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

Deprecated. Use getRelativeJacobian() instead.

◆ getLocalJacobian() [2/2]

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

Deprecated. Use getRelativeJacobian() instead.

◆ getLocalJacobianTimeDeriv()

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

Deprecated. Use getRelativeJacobianTimeDeriv() instead.

◆ getLocalPrimaryAcceleration()

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

Deprecated. Use getLocalPrimaryAcceleration() instead.

◆ getLocalSpatialAcceleration()

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

Deprecated. Use getLocalSpatialAcceleration() instead.

◆ getLocalSpatialVelocity()

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

Deprecated. Use getLocalSpatialVelocity() instead.

◆ getLocalTransform()

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

Deprecated. Use getRelativeTransform() instead.

◆ getName()

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

Get joint name.

◆ getNumDofs()

std::size_t dart::dynamics::ZeroDofJoint::getNumDofs ( ) const
overridevirtual

Get number of generalized coordinates.

Implements dart::dynamics::Joint.

◆ getParentBodyNode() [1/2]

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

Get the parent BodyNode of this Joint.

◆ getParentBodyNode() [2/2]

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

Get the (const) parent BodyNode of this Joint.

◆ getPosition()

double dart::dynamics::ZeroDofJoint::getPosition ( std::size_t  _index) const
overridevirtual

Get the position of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ getPositionDifferences()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getPositionDifferences ( const Eigen::VectorXd &  _q2,
const Eigen::VectorXd &  _q1 
) const
overridevirtual

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

Implements dart::dynamics::Joint.

◆ getPositionLowerLimit()

double dart::dynamics::ZeroDofJoint::getPositionLowerLimit ( std::size_t  _index) const
overridevirtual

Get lower limit for position.

Implements dart::dynamics::Joint.

◆ getPositionLowerLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getPositionLowerLimits ( ) const
overridevirtual

Get the position lower limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getPositions()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getPositions ( ) const
overridevirtual

Get the positions of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ getPositionUpperLimit()

double dart::dynamics::ZeroDofJoint::getPositionUpperLimit ( std::size_t  _index) const
overridevirtual

Get upper limit for position.

Implements dart::dynamics::Joint.

◆ getPositionUpperLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getPositionUpperLimits ( ) const
overridevirtual

Get the position upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getPotentialEnergy()

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

Get potential energy.

◆ getRelativeJacobian() [1/2]

const math::Jacobian dart::dynamics::ZeroDofJoint::getRelativeJacobian ( ) const
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ getRelativeJacobian() [2/2]

math::Jacobian dart::dynamics::ZeroDofJoint::getRelativeJacobian ( const Eigen::VectorXd &  positions) const
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ getRelativeJacobianTimeDeriv()

const math::Jacobian dart::dynamics::ZeroDofJoint::getRelativeJacobianTimeDeriv ( ) const
overrideprotectedvirtual

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

Implements dart::dynamics::Joint.

◆ getRelativePrimaryAcceleration()

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

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

◆ getRelativeSpatialAcceleration()

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

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
inherited

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
inherited

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

◆ getRestPosition()

double dart::dynamics::ZeroDofJoint::getRestPosition ( std::size_t  _index) const
overridevirtual

Get rest position of spring force.

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

Implements dart::dynamics::Joint.

◆ getSkeleton() [1/2]

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

Get the Skeleton that this Joint belongs to.

◆ getSkeleton() [2/2]

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

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

◆ getSpatialToGeneralized()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getSpatialToGeneralized ( const Eigen::Vector6d _spatial)
overrideprotectedvirtual

Implements dart::dynamics::Joint.

◆ getSpringStiffness()

double dart::dynamics::ZeroDofJoint::getSpringStiffness ( std::size_t  _index) const
overridevirtual

Get stiffness of joint spring force.

Parameters
[in]_indexIndex of joint axis.

Implements dart::dynamics::Joint.

◆ getTransformFromChildBodyNode()

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

Get transformation from child body node to this joint.

◆ getTransformFromParentBodyNode()

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

Get transformation from parent body node to this joint.

◆ getTreeIndex()

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

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

◆ getType()

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

Gets a string representing the joint type.

Implemented in dart::dynamics::WeldJoint.

◆ getVelocities()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getVelocities ( ) const
overridevirtual

Get the velocities of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ getVelocity()

double dart::dynamics::ZeroDofJoint::getVelocity ( std::size_t  _index) const
overridevirtual

Get the velocity of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ getVelocityChange()

double dart::dynamics::ZeroDofJoint::getVelocityChange ( std::size_t  _index) const
overridevirtual

Get a single velocity change.

Implements dart::dynamics::Joint.

◆ getVelocityLowerLimit()

double dart::dynamics::ZeroDofJoint::getVelocityLowerLimit ( std::size_t  _index) const
overridevirtual

Get lower limit for velocity.

Implements dart::dynamics::Joint.

◆ getVelocityLowerLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getVelocityLowerLimits ( ) const
overridevirtual

Get the velocity lower limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getVelocityUpperLimit()

double dart::dynamics::ZeroDofJoint::getVelocityUpperLimit ( std::size_t  _index) const
overridevirtual

Get upper limit for velocity.

Implements dart::dynamics::Joint.

◆ getVelocityUpperLimits()

Eigen::VectorXd dart::dynamics::ZeroDofJoint::getVelocityUpperLimits ( ) const
overridevirtual

Get the velocity upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ getVersion()

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

Get the version number of this object.

◆ getZeroDofJointProperties()

ZeroDofJoint::Properties dart::dynamics::ZeroDofJoint::getZeroDofJointProperties ( ) const

Get the Properties of this ZeroDofJoint.

◆ hasJointAspect()

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

Check if this Composite currently has JointAspect .

◆ hasPositionLimit()

bool dart::dynamics::ZeroDofJoint::hasPositionLimit ( std::size_t  _index) const
overridevirtual

Get whether the position of a generalized coordinate has limits.

Implements dart::dynamics::Joint.

◆ incrementVersion()

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

Increment the version for this object.

◆ integratePositions()

void dart::dynamics::ZeroDofJoint::integratePositions ( double  _dt)
overridevirtual

Integrate positions using Euler method.

Implements dart::dynamics::Joint.

◆ integrateVelocities()

void dart::dynamics::ZeroDofJoint::integrateVelocities ( double  _dt)
overridevirtual

Integrate velocities using Euler method.

Implements dart::dynamics::Joint.

◆ isCyclic()

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

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()

bool dart::dynamics::ZeroDofJoint::isDofNamePreserved ( std::size_t  _index) const
overridevirtual

◆ isDynamic()

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

Return true if this joint is dynamic joint.

◆ isKinematic()

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

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
inherited

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 ( )
inherited

Notify that an acceleration has updated.

◆ notifyAccelerationUpdated()

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

Notify that an acceleration has updated.

◆ notifyPositionUpdate()

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

Notify that a position has updated.

◆ notifyPositionUpdated()

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

Notify that a position has updated.

◆ notifyVelocityUpdate()

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

Notify that a velocity has updated.

◆ notifyVelocityUpdated()

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

Notify that a velocity has updated.

◆ preserveDofName()

void dart::dynamics::ZeroDofJoint::preserveDofName ( std::size_t  _index,
bool  _preserve 
)
overridevirtual

◆ registerDofs()

void dart::dynamics::ZeroDofJoint::registerDofs ( )
overrideprotectedvirtual

Called by the Skeleton class.

Implements dart::dynamics::Joint.

◆ releaseJointAspect()

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

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 ( )
inlineinherited

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()

void dart::dynamics::ZeroDofJoint::resetAccelerations ( )
overridevirtual

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

Implements dart::dynamics::Joint.

◆ resetCommands()

void dart::dynamics::ZeroDofJoint::resetCommands ( )
overridevirtual

Set all the commands for this Joint to zero.

Implements dart::dynamics::Joint.

◆ resetConstraintImpulses()

void dart::dynamics::ZeroDofJoint::resetConstraintImpulses ( )
overridevirtual

Set zero all the constraint impulses.

Implements dart::dynamics::Joint.

◆ resetForces()

void dart::dynamics::ZeroDofJoint::resetForces ( )
overridevirtual

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

Implements dart::dynamics::Joint.

◆ resetPosition()

void dart::dynamics::ZeroDofJoint::resetPosition ( std::size_t  _index)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ resetPositions()

void dart::dynamics::ZeroDofJoint::resetPositions ( )
overridevirtual

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

Implements dart::dynamics::Joint.

◆ resetTotalImpulses()

void dart::dynamics::ZeroDofJoint::resetTotalImpulses ( )
overrideprotectedvirtual

Set total impulses to zero.

Implements dart::dynamics::Joint.

◆ resetVelocities()

void dart::dynamics::ZeroDofJoint::resetVelocities ( )
overridevirtual

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

Implements dart::dynamics::Joint.

◆ resetVelocity()

void dart::dynamics::ZeroDofJoint::resetVelocity ( std::size_t  _index)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ resetVelocityChanges()

void dart::dynamics::ZeroDofJoint::resetVelocityChanges ( )
overridevirtual

Set zero all the velocity change.

Implements dart::dynamics::Joint.

◆ 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()

void dart::dynamics::ZeroDofJoint::setAcceleration ( std::size_t  _index,
double  _acceleration 
)
overridevirtual

Set the acceleration of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ setAccelerationLowerLimit()

void dart::dynamics::ZeroDofJoint::setAccelerationLowerLimit ( std::size_t  _index,
double  _acceleration 
)
overridevirtual

Set lower limit for acceleration.

Implements dart::dynamics::Joint.

◆ setAccelerationLowerLimits()

void dart::dynamics::ZeroDofJoint::setAccelerationLowerLimits ( const Eigen::VectorXd &  lowerLimits)
overridevirtual

Set the acceleration upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setAccelerations()

void dart::dynamics::ZeroDofJoint::setAccelerations ( const Eigen::VectorXd &  _accelerations)
overridevirtual

Set the accelerations of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ setAccelerationUpperLimit()

void dart::dynamics::ZeroDofJoint::setAccelerationUpperLimit ( std::size_t  _index,
double  _acceleration 
)
overridevirtual

Set upper limit for acceleration.

Implements dart::dynamics::Joint.

◆ setAccelerationUpperLimits()

void dart::dynamics::ZeroDofJoint::setAccelerationUpperLimits ( const Eigen::VectorXd &  upperLimits)
overridevirtual

Set the acceleration upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setActuatorType()

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

Set actuator type.

◆ setAspectProperties()

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

Set the AspectProperties of this Joint.

◆ setCommand()

void dart::dynamics::ZeroDofJoint::setCommand ( std::size_t  _index,
double  _command 
)
overridevirtual

Set a single command.

Implements dart::dynamics::Joint.

◆ setCommands()

void dart::dynamics::ZeroDofJoint::setCommands ( const Eigen::VectorXd &  _commands)
overridevirtual

Set all commands for this Joint.

Implements dart::dynamics::Joint.

◆ setConstraintImpulse()

void dart::dynamics::ZeroDofJoint::setConstraintImpulse ( std::size_t  _index,
double  _impulse 
)
overridevirtual

Set a single constraint impulse.

Implements dart::dynamics::Joint.

◆ setCoulombFriction()

void dart::dynamics::ZeroDofJoint::setCoulombFriction ( std::size_t  _index,
double  _friction 
)
overridevirtual

Set joint Coulomb friction froce.

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

Implements dart::dynamics::Joint.

◆ setDampingCoefficient()

void dart::dynamics::ZeroDofJoint::setDampingCoefficient ( std::size_t  _index,
double  _coeff 
)
overridevirtual

Set coefficient of joint damping (viscous friction) force.

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

Implements dart::dynamics::Joint.

◆ setDofName()

const std::string & dart::dynamics::ZeroDofJoint::setDofName ( std::size_t  _index,
const std::string &  _name,
bool  _preserveName 
)
overridevirtual

◆ setForce()

void dart::dynamics::ZeroDofJoint::setForce ( std::size_t  _index,
double  _force 
)
overridevirtual

Set the force of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ setForceLowerLimit()

void dart::dynamics::ZeroDofJoint::setForceLowerLimit ( std::size_t  _index,
double  _force 
)
overridevirtual

Set lower limit for force.

Implements dart::dynamics::Joint.

◆ setForceLowerLimits()

void dart::dynamics::ZeroDofJoint::setForceLowerLimits ( const Eigen::VectorXd &  lowerLimits)
overridevirtual

Set the force upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setForces()

void dart::dynamics::ZeroDofJoint::setForces ( const Eigen::VectorXd &  _forces)
overridevirtual

Set the forces of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ setForceUpperLimit()

void dart::dynamics::ZeroDofJoint::setForceUpperLimit ( std::size_t  _index,
double  _force 
)
overridevirtual

Set upper limit for force.

Implements dart::dynamics::Joint.

◆ setForceUpperLimits()

void dart::dynamics::ZeroDofJoint::setForceUpperLimits ( const Eigen::VectorXd &  upperLimits)
overridevirtual

Set the force upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setInitialPosition()

void dart::dynamics::ZeroDofJoint::setInitialPosition ( std::size_t  _index,
double  _initial 
)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ setInitialPositions()

void dart::dynamics::ZeroDofJoint::setInitialPositions ( const Eigen::VectorXd &  _initial)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ setInitialVelocities()

void dart::dynamics::ZeroDofJoint::setInitialVelocities ( const Eigen::VectorXd &  _initial)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ setInitialVelocity()

void dart::dynamics::ZeroDofJoint::setInitialVelocity ( std::size_t  _index,
double  _initial 
)
overridevirtual

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

Implements dart::dynamics::Joint.

◆ setJointAspect() [1/2]

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

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)
inlineinherited

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 
)
inherited

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()

void dart::dynamics::ZeroDofJoint::setPartialAccelerationTo ( Eigen::Vector6d _partialAcceleration,
const Eigen::Vector6d _childVelocity 
)
overrideprotectedvirtual

Set joint partial acceleration to _partialAcceleration.

Implements dart::dynamics::Joint.

◆ setPosition()

void dart::dynamics::ZeroDofJoint::setPosition ( std::size_t  _index,
double  _position 
)
overridevirtual

Set the position of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ setPositionLimitEnforced()

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

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()

void dart::dynamics::ZeroDofJoint::setPositionLowerLimit ( std::size_t  _index,
double  _position 
)
overridevirtual

Set lower limit for position.

Implements dart::dynamics::Joint.

◆ setPositionLowerLimits()

void dart::dynamics::ZeroDofJoint::setPositionLowerLimits ( const Eigen::VectorXd &  lowerLimits)
overridevirtual

Set the position lower limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setPositions()

void dart::dynamics::ZeroDofJoint::setPositions ( const Eigen::VectorXd &  _positions)
overridevirtual

Set the positions of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ setPositionUpperLimit()

void dart::dynamics::ZeroDofJoint::setPositionUpperLimit ( std::size_t  _index,
double  _position 
)
overridevirtual

Set upper limit for position.

Implements dart::dynamics::Joint.

◆ setPositionUpperLimits()

void dart::dynamics::ZeroDofJoint::setPositionUpperLimits ( const Eigen::VectorXd &  upperLimits)
overridevirtual

Set the position upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setProperties()

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

Set the Properties of this Joint.

◆ setRestPosition()

void dart::dynamics::ZeroDofJoint::setRestPosition ( std::size_t  _index,
double  _q0 
)
overridevirtual

Set rest position of spring force.

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

Implements dart::dynamics::Joint.

◆ setSpringStiffness()

void dart::dynamics::ZeroDofJoint::setSpringStiffness ( std::size_t  _index,
double  _k 
)
overridevirtual

Set stiffness of joint spring force.

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

Implements dart::dynamics::Joint.

◆ setTransformFromChildBodyNode()

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

Set transformation from child body node to this joint.

Reimplemented in dart::dynamics::WeldJoint.

◆ setTransformFromParentBodyNode()

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

Set transformation from parent body node to this joint.

Reimplemented in dart::dynamics::WeldJoint.

◆ setVelocities()

void dart::dynamics::ZeroDofJoint::setVelocities ( const Eigen::VectorXd &  _velocities)
overridevirtual

Set the velocities of all generalized coordinates in this Joint.

Implements dart::dynamics::Joint.

◆ setVelocity()

void dart::dynamics::ZeroDofJoint::setVelocity ( std::size_t  _index,
double  _velocity 
)
overridevirtual

Set the velocity of a single generalized coordinate.

Implements dart::dynamics::Joint.

◆ setVelocityChange()

void dart::dynamics::ZeroDofJoint::setVelocityChange ( std::size_t  _index,
double  _velocityChange 
)
overridevirtual

Set a single velocity change.

Implements dart::dynamics::Joint.

◆ setVelocityLowerLimit()

void dart::dynamics::ZeroDofJoint::setVelocityLowerLimit ( std::size_t  _index,
double  _velocity 
)
overridevirtual

Set lower limit for velocity.

Implements dart::dynamics::Joint.

◆ setVelocityLowerLimits()

void dart::dynamics::ZeroDofJoint::setVelocityLowerLimits ( const Eigen::VectorXd &  lowerLimits)
overridevirtual

Set the velocity lower limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setVelocityUpperLimit()

void dart::dynamics::ZeroDofJoint::setVelocityUpperLimit ( std::size_t  _index,
double  _velocity 
)
overridevirtual

Set upper limit for velocity.

Implements dart::dynamics::Joint.

◆ setVelocityUpperLimits()

void dart::dynamics::ZeroDofJoint::setVelocityUpperLimits ( const Eigen::VectorXd &  upperLimits)
overridevirtual

Set the velocity upper limits of all the generalized coordinates.

Implements dart::dynamics::Joint.

◆ setVersionDependentObject()

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

◆ updateAcceleration()

void dart::dynamics::ZeroDofJoint::updateAcceleration ( const Eigen::Matrix6d _artInertia,
const Eigen::Vector6d _spatialAcc 
)
overrideprotectedvirtual

Update joint acceleration.

Implements dart::dynamics::Joint.

◆ updateArticulatedInertia()

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

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

◆ updateConstrainedTerms()

void dart::dynamics::ZeroDofJoint::updateConstrainedTerms ( double  _timeStep)
overrideprotectedvirtual

Update constrained terms for forward dynamics.

Implements dart::dynamics::Joint.

◆ updateDegreeOfFreedomNames()

void dart::dynamics::ZeroDofJoint::updateDegreeOfFreedomNames ( )
overrideprotectedvirtual

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

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

Implements dart::dynamics::Joint.

◆ updateForceFD()

void dart::dynamics::ZeroDofJoint::updateForceFD ( const Eigen::Vector6d _bodyForce,
double  _timeStep,
bool  _withDampingForcese,
bool  _withSpringForces 
)
overrideprotectedvirtual

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.

Implements dart::dynamics::Joint.

◆ updateForceID()

void dart::dynamics::ZeroDofJoint::updateForceID ( const Eigen::Vector6d _bodyForce,
double  _timeStep,
bool  _withDampingForces,
bool  _withSpringForces 
)
overrideprotectedvirtual

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.

Implements dart::dynamics::Joint.

◆ updateImpulseFD()

void dart::dynamics::ZeroDofJoint::updateImpulseFD ( const Eigen::Vector6d _bodyImpulse)
overrideprotectedvirtual

Update joint impulses for forward dynamics.

Implements dart::dynamics::Joint.

◆ updateImpulseID()

void dart::dynamics::ZeroDofJoint::updateImpulseID ( const Eigen::Vector6d _bodyImpulse)
overrideprotectedvirtual

Update joint impulses for inverse dynamics.

Implements dart::dynamics::Joint.

◆ updateInvProjArtInertia()

void dart::dynamics::ZeroDofJoint::updateInvProjArtInertia ( const Eigen::Matrix6d _artInertia)
overrideprotectedvirtual

Update inverse of projected articulated body inertia.

Implements dart::dynamics::Joint.

◆ updateInvProjArtInertiaImplicit()

void dart::dynamics::ZeroDofJoint::updateInvProjArtInertiaImplicit ( const Eigen::Matrix6d _artInertia,
double  _timeStep 
)
overrideprotectedvirtual

Forward dynamics routine.

Implements dart::dynamics::Joint.

◆ updateLocalJacobian()

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

Deprecated. Use updateRelativeJacobian() instead.

◆ updateLocalJacobianTimeDeriv()

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

Deprecated. Use updateRelativeJacobianTimeDeriv() instead.

◆ updateLocalPrimaryAcceleration()

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

Deprecated. Use updateRelativePrimaryAcceleration() instead.

◆ updateLocalSpatialAcceleration()

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

Deprecated. Use updateRelativeSpatialAcceleration() instead.

◆ updateLocalSpatialVelocity()

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

Deprecated. Use updateRelativeSpatialVelocity() instead.

◆ updateLocalTransform()

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

Deprecated. Use updateRelativeTransform() instead.

◆ updateRelativeJacobian()

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

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 virtualinherited

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 virtualinherited

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

Implemented in dart::dynamics::WeldJoint.

◆ updateRelativeSpatialAcceleration()

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

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 virtualinherited

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 virtualinherited

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

Implemented in dart::dynamics::WeldJoint.

◆ updateTotalForce()

void dart::dynamics::ZeroDofJoint::updateTotalForce ( const Eigen::Vector6d _bodyForce,
double  _timeStep 
)
overrideprotectedvirtual

Update joint total force.

Implements dart::dynamics::Joint.

◆ updateTotalForceForInvMassMatrix()

void dart::dynamics::ZeroDofJoint::updateTotalForceForInvMassMatrix ( const Eigen::Vector6d _bodyForce)
overrideprotectedvirtual

Implements dart::dynamics::Joint.

◆ updateTotalImpulse()

void dart::dynamics::ZeroDofJoint::updateTotalImpulse ( const Eigen::Vector6d _bodyImpulse)
overrideprotectedvirtual

Update joint total impulse.

Implements dart::dynamics::Joint.

◆ updateVelocityChange()

void dart::dynamics::ZeroDofJoint::updateVelocityChange ( const Eigen::Matrix6d _artInertia,
const Eigen::Vector6d _velocityChange 
)
overrideprotectedvirtual

Update joint velocity change.

Parameters
_artInertia
_velocityChange

Implements dart::dynamics::Joint.

Member Data Documentation

◆ ACCELERATION

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

◆ DefaultActuatorType

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

Default actuator type.

◆ emptyString

const std::string dart::dynamics::ZeroDofJoint::emptyString
private

Used by getDofName()

◆ FORCE

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

◆ LOCKED

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

◆ mAspectProperties

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

◆ mChildBodyNode

BodyNode* dart::dynamics::Joint::mChildBodyNode
protectedinherited

Child BodyNode pointer that this Joint belongs to.

◆ mDependent

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

◆ mIsRelativeJacobianDirty

bool dart::dynamics::Joint::mIsRelativeJacobianDirty
mutableprotectedinherited

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

◆ mIsRelativeJacobianTimeDerivDirty

bool dart::dynamics::Joint::mIsRelativeJacobianTimeDerivDirty
mutableprotectedinherited

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
mutableprotectedinherited

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

◆ mNeedSpatialAccelerationUpdate

bool dart::dynamics::Joint::mNeedSpatialAccelerationUpdate
mutableprotectedinherited

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

◆ mNeedSpatialVelocityUpdate

bool dart::dynamics::Joint::mNeedSpatialVelocityUpdate
mutableprotectedinherited

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

◆ mNeedTransformUpdate

bool dart::dynamics::Joint::mNeedTransformUpdate
mutableprotectedinherited

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
mutableprotectedinherited

J * q_dd.

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

◆ mSpatialAcceleration

Eigen::Vector6d dart::dynamics::Joint::mSpatialAcceleration
mutableprotectedinherited

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
mutableprotectedinherited

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
mutableprotectedinherited

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
staticconstexprinherited

◆ SERVO

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

◆ VELOCITY

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