dart
Classes | Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Friends | List of all members
dart::dynamics::Joint Class Referenceabstract

class Joint More...

#include <Joint.hpp>

Inheritance diagram for dart::dynamics::Joint:
Inheritance graph
[legend]
Collaboration diagram for dart::dynamics::Joint:
Collaboration graph
[legend]

Classes

struct  ExtendedProperties
 

Public Types

using CompositeProperties = common::Composite::Properties
 
using Properties = detail::JointProperties
 
typedef detail::ActuatorType ActuatorType
 
- Public Types inherited from dart::common::EmbedProperties< Joint, detail::JointProperties >
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

 Joint (const Joint &)=delete
 
virtual ~Joint ()
 Destructor.
 
void setProperties (const Properties &properties)
 Set the Properties of this Joint.
 
void setAspectProperties (const AspectProperties &properties)
 Set the AspectProperties of this Joint.
 
const PropertiesgetJointProperties () const
 Get the Properties of this Joint.
 
void copy (const Joint &_otherJoint)
 Copy the properties of another Joint.
 
void copy (const Joint *_otherJoint)
 Copy the properties of another Joint.
 
Jointoperator= (const Joint &_otherJoint)
 Same as copy(const Joint&)
 
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.
 
virtual const std::string & getType () const =0
 Gets a string representing the joint type.
 
void setActuatorType (ActuatorType _actuatorType)
 Set actuator type.
 
ActuatorType getActuatorType () const
 Get actuator type.
 
void setMimicJoint (const Joint *_mimicJoint, double _mimicMultiplier=1.0, double _mimicOffset=0.0)
 Set mimic joint.
 
const JointgetMimicJoint () const
 Get mimic joint.
 
double getMimicMultiplier () const
 Get mimic joint multiplier.
 
double getMimicOffset () const
 Get mimic joint offset.
 
bool isKinematic () const
 Return true if this joint is kinematic joint. More...
 
bool isDynamic () const
 Return true if this joint is dynamic joint.
 
BodyNodegetChildBodyNode ()
 Get the child BodyNode of this Joint.
 
const BodyNodegetChildBodyNode () const
 Get the (const) child BodyNode of this Joint.
 
BodyNodegetParentBodyNode ()
 Get the parent BodyNode of this Joint.
 
const BodyNodegetParentBodyNode () const
 Get the (const) parent BodyNode of this Joint.
 
SkeletonPtr getSkeleton ()
 Get the Skeleton that this Joint belongs to.
 
std::shared_ptr< const SkeletongetSkeleton () const
 Get the (const) Skeleton that this Joint belongs to.
 
virtual void setTransformFromParentBodyNode (const Eigen::Isometry3d &_T)
 Set transformation from parent body node to this joint.
 
virtual void setTransformFromChildBodyNode (const Eigen::Isometry3d &_T)
 Set transformation from child body node to this joint.
 
const Eigen::Isometry3d & getTransformFromParentBodyNode () const
 Get transformation from parent body node to this joint.
 
const Eigen::Isometry3d & getTransformFromChildBodyNode () const
 Get transformation from child body node to this joint.
 
void setPositionLimitEnforced (bool enforced)
 Sets whether enforcing joint position and velocity limits. More...
 
void setLimitEnforcement (bool enforced)
 Sets whether enforcing joint position and velocity limits. More...
 
bool isPositionLimitEnforced () const
 Returns whether enforcing joint position limit. More...
 
bool areLimitsEnforced () const
 Returns whether enforcing joint position and velocity limits. 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.
 
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.
 
std::size_t getJointIndexInSkeleton () const
 Get the index of this Joint within its Skeleton.
 
std::size_t getJointIndexInTree () const
 Get the index of this Joint within its tree.
 
std::size_t getTreeIndex () const
 Get the index of the tree that this Joint belongs to.
 
virtual DegreeOfFreedomgetDof (std::size_t _index)=0
 Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
 
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.
 
virtual const std::string & setDofName (std::size_t _index, const std::string &_name, bool _preserveName=true)=0
 Alternative to DegreeOfFreedom::setName()
 
virtual void preserveDofName (std::size_t _index, bool _preserve)=0
 Alternative to DegreeOfFreedom::preserveName()
 
virtual bool isDofNamePreserved (std::size_t _index) const =0
 Alternative to DegreeOfFreedom::isNamePreserved()
 
virtual const std::string & getDofName (std::size_t _index) const =0
 Alternative to DegreeOfFreedom::getName()
 
virtual std::size_t getNumDofs () const =0
 Get number of generalized coordinates.
 
double getPotentialEnergy () const
 Get potential energy.
 
virtual double computePotentialEnergy () const =0
 Compute and return the potential energy.
 
const Eigen::Isometry3d & getLocalTransform () const
 Deprecated. Use getRelativeTransform() instead.
 
const Eigen::Vector6d & getLocalSpatialVelocity () const
 Deprecated. Use getLocalSpatialVelocity() instead.
 
const Eigen::Vector6d & getLocalSpatialAcceleration () const
 Deprecated. Use getLocalSpatialAcceleration() instead.
 
const Eigen::Vector6d & getLocalPrimaryAcceleration () const
 Deprecated. Use getLocalPrimaryAcceleration() instead.
 
const math::Jacobian getLocalJacobian () const
 Deprecated. Use getRelativeJacobian() instead.
 
math::Jacobian getLocalJacobian (const Eigen::VectorXd &positions) const
 Deprecated. Use getRelativeJacobian() instead.
 
const math::Jacobian getLocalJacobianTimeDeriv () const
 Deprecated. Use getRelativeJacobianTimeDeriv() instead.
 
const Eigen::Isometry3d & getRelativeTransform () const
 Get transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
 
const Eigen::Vector6d & getRelativeSpatialVelocity () const
 Get spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
 
const Eigen::Vector6d & getRelativeSpatialAcceleration () const
 Get spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
 
const Eigen::Vector6d & getRelativePrimaryAcceleration () const
 Get J * \( \ddot{q} \) of this joint.
 
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.
 
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.
 
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.
 
virtual Eigen::Vector6d getBodyConstraintWrench () const =0
 Get constraint wrench expressed in body node frame.
 
Command
virtual void setCommand (std::size_t _index, double _command)=0
 Set a single command.
 
virtual double getCommand (std::size_t _index) const =0
 Get a single command.
 
virtual void setCommands (const Eigen::VectorXd &_commands)=0
 Set all commands for this Joint.
 
virtual Eigen::VectorXd getCommands () const =0
 Get all commands for this Joint.
 
virtual void resetCommands ()=0
 Set all the commands for this Joint to zero.
 
Position
virtual void setPosition (std::size_t _index, double _position)=0
 Set the position of a single generalized coordinate.
 
virtual double getPosition (std::size_t _index) const =0
 Get the position of a single generalized coordinate.
 
virtual void setPositions (const Eigen::VectorXd &_positions)=0
 Set the positions of all generalized coordinates in this Joint.
 
virtual Eigen::VectorXd getPositions () const =0
 Get the positions of all generalized coordinates in this Joint.
 
virtual void setPositionLowerLimit (std::size_t _index, double _position)=0
 Set lower limit for position.
 
virtual double getPositionLowerLimit (std::size_t _index) const =0
 Get lower limit for position.
 
virtual void setPositionLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the position lower limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getPositionLowerLimits () const =0
 Get the position lower limits of all the generalized coordinates.
 
virtual void setPositionUpperLimit (std::size_t _index, double _position)=0
 Set upper limit for position.
 
virtual double getPositionUpperLimit (std::size_t _index) const =0
 Get upper limit for position.
 
virtual void setPositionUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the position upper limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getPositionUpperLimits () const =0
 Get the position upper limits of all the generalized coordinates.
 
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.
 
virtual void resetPosition (std::size_t _index)=0
 Set the position of this generalized coordinate to its initial position.
 
virtual void resetPositions ()=0
 Set the positions of all generalized coordinates in this Joint to their initial positions.
 
virtual void setInitialPosition (std::size_t _index, double _initial)=0
 Change the position that resetPositions() will give to this coordinate.
 
virtual double getInitialPosition (std::size_t _index) const =0
 Get the position that resetPosition() will give to this coordinate.
 
virtual void setInitialPositions (const Eigen::VectorXd &_initial)=0
 Change the positions that resetPositions() will give to this Joint's coordinates.
 
virtual Eigen::VectorXd getInitialPositions () const =0
 Get the positions that resetPositions() will give to this Joint's coordinates.
 
Velocity
virtual void setVelocity (std::size_t _index, double _velocity)=0
 Set the velocity of a single generalized coordinate.
 
virtual double getVelocity (std::size_t _index) const =0
 Get the velocity of a single generalized coordinate.
 
virtual void setVelocities (const Eigen::VectorXd &_velocities)=0
 Set the velocities of all generalized coordinates in this Joint.
 
virtual Eigen::VectorXd getVelocities () const =0
 Get the velocities of all generalized coordinates in this Joint.
 
virtual void setVelocityLowerLimit (std::size_t _index, double _velocity)=0
 Set lower limit for velocity.
 
virtual double getVelocityLowerLimit (std::size_t _index) const =0
 Get lower limit for velocity.
 
virtual void setVelocityLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the velocity lower limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getVelocityLowerLimits () const =0
 Get the velocity lower limits of all the generalized coordinates.
 
virtual void setVelocityUpperLimit (std::size_t _index, double _velocity)=0
 Set upper limit for velocity.
 
virtual double getVelocityUpperLimit (std::size_t _index) const =0
 Get upper limit for velocity.
 
virtual void setVelocityUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the velocity upper limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getVelocityUpperLimits () const =0
 Get the velocity upper limits of all the generalized coordinates.
 
virtual void resetVelocity (std::size_t _index)=0
 Set the velocity of a generalized coordinate in this Joint to its initial velocity.
 
virtual void resetVelocities ()=0
 Set the velocities of all generalized coordinates in this Joint to their initial velocities.
 
virtual void setInitialVelocity (std::size_t _index, double _initial)=0
 Change the velocity that resetVelocity() will give to this coordinate.
 
virtual double getInitialVelocity (std::size_t _index) const =0
 Get the velocity that resetVelocity() will give to this coordinate.
 
virtual void setInitialVelocities (const Eigen::VectorXd &_initial)=0
 Change the velocities that resetVelocities() will give to this Joint's coordinates.
 
virtual Eigen::VectorXd getInitialVelocities () const =0
 Get the velocities that resetVelocities() will give to this Joint's coordinates.
 
Acceleration
virtual void setAcceleration (std::size_t _index, double _acceleration)=0
 Set the acceleration of a single generalized coordinate.
 
virtual double getAcceleration (std::size_t _index) const =0
 Get the acceleration of a single generalized coordinate.
 
virtual void setAccelerations (const Eigen::VectorXd &_accelerations)=0
 Set the accelerations of all generalized coordinates in this Joint.
 
virtual Eigen::VectorXd getAccelerations () const =0
 Get the accelerations of all generalized coordinates in this Joint.
 
virtual void resetAccelerations ()=0
 Set the accelerations of all generalized coordinates in this Joint to zero.
 
virtual void setAccelerationLowerLimit (std::size_t _index, double _acceleration)=0
 Set lower limit for acceleration.
 
virtual double getAccelerationLowerLimit (std::size_t _index) const =0
 Get lower limit for acceleration.
 
virtual void setAccelerationLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the acceleration upper limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getAccelerationLowerLimits () const =0
 Get the acceleration upper limits of all the generalized coordinates.
 
virtual void setAccelerationUpperLimit (std::size_t _index, double _acceleration)=0
 Set upper limit for acceleration.
 
virtual double getAccelerationUpperLimit (std::size_t _index) const =0
 Get upper limit for acceleration.
 
virtual void setAccelerationUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the acceleration upper limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getAccelerationUpperLimits () const =0
 Get the acceleration upper limits of all the generalized coordinates.
 
Force
virtual void setForce (std::size_t _index, double _force)=0
 Set the force of a single generalized coordinate.
 
virtual double getForce (std::size_t _index) const =0
 Get the force of a single generalized coordinate.
 
virtual void setForces (const Eigen::VectorXd &_forces)=0
 Set the forces of all generalized coordinates in this Joint.
 
virtual Eigen::VectorXd getForces () const =0
 Get the forces of all generalized coordinates in this Joint.
 
virtual void resetForces ()=0
 Set the forces of all generalized coordinates in this Joint to zero.
 
virtual void setForceLowerLimit (std::size_t _index, double _force)=0
 Set lower limit for force.
 
virtual double getForceLowerLimit (std::size_t _index) const =0
 Get lower limit for force.
 
virtual void setForceLowerLimits (const Eigen::VectorXd &lowerLimits)=0
 Set the force upper limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getForceLowerLimits () const =0
 Get the force upper limits of all the generalized coordinates.
 
virtual void setForceUpperLimit (std::size_t _index, double _force)=0
 Set upper limit for force.
 
virtual double getForceUpperLimit (std::size_t _index) const =0
 Get upper limit for force.
 
virtual void setForceUpperLimits (const Eigen::VectorXd &upperLimits)=0
 Set the force upper limits of all the generalized coordinates.
 
virtual Eigen::VectorXd getForceUpperLimits () const =0
 Get the force upper limits of all the generalized coordinates.
 
Sanity Check
bool checkSanity (bool _printWarnings=true) const
 Returns false if the initial position or initial velocity are outside of limits.
 
Velocity change
virtual void setVelocityChange (std::size_t _index, double _velocityChange)=0
 Set a single velocity change.
 
virtual double getVelocityChange (std::size_t _index) const =0
 Get a single velocity change.
 
virtual void resetVelocityChanges ()=0
 Set zero all the velocity change.
 
Constraint impulse
virtual void setConstraintImpulse (std::size_t _index, double _impulse)=0
 Set a single constraint impulse.
 
virtual double getConstraintImpulse (std::size_t _index) const =0
 Get a single constraint impulse.
 
virtual void resetConstraintImpulses ()=0
 Set zero all the constraint impulses.
 
Integration and finite difference
virtual void integratePositions (double _dt)=0
 Integrate positions using Euler method.
 
virtual void integrateVelocities (double _dt)=0
 Integrate velocities using Euler method.
 
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.
 
void notifyPositionUpdated ()
 Notify that a position has updated.
 
void notifyVelocityUpdate ()
 Notify that a velocity has updated.
 
void notifyVelocityUpdated ()
 Notify that a velocity has updated.
 
void notifyAccelerationUpdate ()
 Notify that an acceleration has updated.
 
void notifyAccelerationUpdated ()
 Notify that an acceleration has updated.
 
- Public Member Functions inherited from dart::common::Subject
virtual ~Subject ()
 Destructor will notify all Observers that it is destructing.
 
- Public Member Functions inherited from dart::common::VersionCounter
 VersionCounter ()
 Default constructor.
 
virtual std::size_t incrementVersion ()
 Increment the version for this object.
 
virtual std::size_t getVersion () const
 Get the version number of this object.
 
- Public Member Functions inherited from dart::common::EmbedProperties< Joint, detail::JointProperties >
 EmbedProperties (Args &&... args)
 
const AspectProperties & getAspectProperties () const
 

Static Public Attributes

static constexpr ActuatorType FORCE = detail::FORCE
 
static constexpr ActuatorType PASSIVE = detail::PASSIVE
 
static constexpr ActuatorType SERVO = detail::SERVO
 
static constexpr ActuatorType MIMIC = detail::MIMIC
 
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.
 

Protected Member Functions

 Joint ()
 Constructor called by inheriting class.
 
virtual Jointclone () const =0
 Create a clone of this Joint. More...
 
virtual void registerDofs ()=0
 Called by the Skeleton class.
 
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...
 
Recursive dynamics routines
void updateLocalTransform () const
 Deprecated. Use updateRelativeTransform() instead.
 
void updateLocalSpatialVelocity () const
 Deprecated. Use updateRelativeSpatialVelocity() instead.
 
void updateLocalSpatialAcceleration () const
 Deprecated. Use updateRelativeSpatialAcceleration() instead.
 
void updateLocalPrimaryAcceleration () const
 Deprecated. Use updateRelativePrimaryAcceleration() instead.
 
void updateLocalJacobian (bool mandatory=true) const
 Deprecated. Use updateRelativeJacobian() instead.
 
void updateLocalJacobianTimeDeriv () const
 Deprecated. Use updateRelativeJacobianTimeDeriv() instead.
 
virtual void updateRelativeTransform () const =0
 Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
 
virtual void updateRelativeSpatialVelocity () const =0
 Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
 
virtual void updateRelativeSpatialAcceleration () const =0
 Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
 
virtual void updateRelativePrimaryAcceleration () const =0
 Update J * \( \ddot{q} \) of this joint.
 
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.
 
virtual void addVelocityTo (Eigen::Vector6d &_vel)=0
 Add joint velocity to _vel.
 
virtual void setPartialAccelerationTo (Eigen::Vector6d &_partialAcceleration, const Eigen::Vector6d &_childVelocity)=0
 Set joint partial acceleration to _partialAcceleration.
 
virtual void addAccelerationTo (Eigen::Vector6d &_acc)=0
 Add joint acceleration to _acc.
 
virtual void addVelocityChangeTo (Eigen::Vector6d &_velocityChange)=0
 Add joint velocity change to _velocityChange.
 
virtual void addChildArtInertiaTo (Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia)=0
 Add child's articulated inertia to parent's one.
 
virtual void addChildArtInertiaImplicitTo (Eigen::Matrix6d &_parentArtInertiaImplicit, const Eigen::Matrix6d &_childArtInertiaImplicit)=0
 Add child's articulated inertia to parent's one. Forward dynamics routine.
 
virtual void updateInvProjArtInertia (const Eigen::Matrix6d &_artInertia)=0
 Update inverse of projected articulated body inertia.
 
virtual void updateInvProjArtInertiaImplicit (const Eigen::Matrix6d &_artInertia, double _timeStep)=0
 Forward dynamics routine.
 
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.
 
virtual void addChildBiasImpulseTo (Eigen::Vector6d &_parentBiasImpulse, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasImpulse)=0
 Add child's bias impulse to parent's one.
 
virtual void updateTotalForce (const Eigen::Vector6d &_bodyForce, double _timeStep)=0
 Update joint total force.
 
virtual void updateTotalImpulse (const Eigen::Vector6d &_bodyImpulse)=0
 Update joint total impulse.
 
virtual void resetTotalImpulses ()=0
 Set total impulses to zero.
 
virtual void updateAcceleration (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
 Update joint acceleration.
 
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 _withDampingForces, bool _withSpringForces)=0
 Update joint force for forward dynamics. More...
 
virtual void updateImpulseID (const Eigen::Vector6d &_bodyImpulse)=0
 Update joint impulses for inverse dynamics.
 
virtual void updateImpulseFD (const Eigen::Vector6d &_bodyImpulse)=0
 Update joint impulses for forward dynamics.
 
virtual void updateConstrainedTerms (double _timeStep)=0
 Update constrained terms for forward dynamics.
 
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.
 
virtual void addChildBiasForceForInvAugMassMatrix (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
 Add child's bias force to parent's one.
 
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 Member Functions inherited from dart::common::Subject
void sendDestructionNotification () const
 Send a destruction notification to all Observers. More...
 
void addObserver (Observer *_observer) const
 Add an Observer to the list of Observers.
 
void removeObserver (Observer *_observer) const
 Remove an Observer from the list of Observers.
 
- Protected Member Functions inherited from dart::common::VersionCounter
void setVersionDependentObject (VersionCounter *dependent)
 

Protected Attributes

BodyNodemChildBodyNode
 Child BodyNode pointer that this Joint belongs to.
 
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()
 
bool mNeedSpatialVelocityUpdate
 True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVelocity()
 
bool mNeedSpatialAccelerationUpdate
 True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativeSpatialAcceleration()
 
bool mNeedPrimaryAccelerationUpdate
 True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativePrimaryAcceleration()
 
bool mIsRelativeJacobianDirty
 True iff this joint's relative Jacobian has not been updated since the last position change.
 
bool mIsRelativeJacobianTimeDerivDirty
 True iff this joint's relative Jacobian time derivative has not been updated since the last position or velocity change.
 
- Protected Attributes inherited from dart::common::Subject
std::set< Observer * > mObservers
 List of current Observers.
 
- Protected Attributes inherited from dart::common::VersionCounter
std::size_t mVersion
 
- Protected Attributes inherited from dart::common::EmbedProperties< Joint, detail::JointProperties >
AspectProperties mAspectProperties
 Aspect::Properties data, directly accessible to your derived class.
 

Friends

class BodyNode
 
class SoftBodyNode
 
class Skeleton
 

Detailed Description

class Joint

Member Function Documentation

◆ areLimitsEnforced()

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

Returns whether enforcing joint position and velocity limits.

This enforcement is only enabled when the actuator type is PASSIVE or FORCE.

See also
ActuatorType

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

◆ createDofPointer()

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

Create a DegreeOfFreedom pointer.

Parameters
[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.

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

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

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

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

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

◆ 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

Returns whether enforcing joint position limit.

This enforcement is only enabled when the actuator type is PASSIVE or FORCE.

See also
ActuatorType
Deprecated:
Deprecated since DART 6.10. Please use areLimitsEnforced() instead

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

◆ setLimitEnforcement()

void dart::dynamics::Joint::setLimitEnforcement ( bool  enforced)

Sets whether enforcing joint position and velocity limits.

This enforcement is only enabled when the actuator type is PASSIVE or FORCE.

See also
ActuatorType

◆ setName()

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

Set joint name and return the name.

Parameters
[in]_nameThe specified joint name to be set.
[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.

◆ setPositionLimitEnforced()

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

Sets whether enforcing joint position and velocity limits.

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

See also
ActuatorType
Deprecated:
Deprecated since DART 6.10. Please use setLimitEnforcement() instead

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

◆ 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  _withDampingForces,
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.
[in]_timeStep
[in]_withDampingForces
[in]_withSpringForces

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.
[in]_timeStep
[in]_withDampingForces
[in]_withSpringForces

Implemented in dart::dynamics::ZeroDofJoint.

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

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

Member Data Documentation

◆ 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


The documentation for this class was generated from the following files: