| DART 6.12.2
    | 
#include <WeldJoint.hpp>
 
  
| 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 | |
| WeldJoint (const WeldJoint &)=delete | |
| virtual | ~WeldJoint () | 
| Destructor. | |
| Properties | getWeldJointProperties () const | 
| Get the Properties of this WeldJoint. | |
| const std::string & | getType () const override | 
| Gets a string representing the joint type. | |
| bool | isCyclic (std::size_t _index) const override | 
| Get whether a generalized coordinate is cyclic. | |
| void | setTransformFromParentBodyNode (const Eigen::Isometry3d &_T) override | 
| Set transformation from parent body node to this joint. | |
| void | setTransformFromChildBodyNode (const Eigen::Isometry3d &_T) override | 
| Set transformation from child body node to this joint. | |
| Properties | getZeroDofJointProperties () const | 
| Get the Properties of this ZeroDofJoint. | |
| DegreeOfFreedom * | getDof (std::size_t) override | 
| Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint. | |
| const DegreeOfFreedom * | getDof (std::size_t) const override | 
| Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint. | |
| const std::string & | setDofName (std::size_t, const std::string &, bool) override | 
| Alternative to DegreeOfFreedom::setName() | |
| void | preserveDofName (std::size_t, bool) override | 
| Alternative to DegreeOfFreedom::preserveName() | |
| bool | isDofNamePreserved (std::size_t) const override | 
| Alternative to DegreeOfFreedom::isNamePreserved() | |
| const std::string & | getDofName (std::size_t) const override | 
| Alternative to DegreeOfFreedom::getName() | |
| std::size_t | getNumDofs () const override | 
| Get number of generalized coordinates. | |
| std::size_t | getIndexInSkeleton (std::size_t _index) const override | 
| Get a unique index in skeleton of a generalized coordinate in this Joint. | |
| 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. | |
| void | setCommand (std::size_t _index, double _command) override | 
| Set a single command. | |
| double | getCommand (std::size_t _index) const override | 
| Get a single command. | |
| void | setCommands (const Eigen::VectorXd &_commands) override | 
| Set all commands for this Joint. | |
| Eigen::VectorXd | getCommands () const override | 
| Get all commands for this Joint. | |
| void | resetCommands () override | 
| Set all the commands for this Joint to zero. | |
| void | setPosition (std::size_t, double) override | 
| Set the position of a single generalized coordinate. | |
| double | getPosition (std::size_t _index) const override | 
| Get the position of a single generalized coordinate. | |
| void | setPositions (const Eigen::VectorXd &_positions) override | 
| Set the positions of all generalized coordinates in this Joint. | |
| Eigen::VectorXd | getPositions () const override | 
| Get the positions of all generalized coordinates in this Joint. | |
| void | setPositionLowerLimit (std::size_t _index, double _position) override | 
| Set lower limit for position. | |
| double | getPositionLowerLimit (std::size_t _index) const override | 
| Get lower limit for position. | |
| void | setPositionLowerLimits (const Eigen::VectorXd &lowerLimits) override | 
| Set the position lower limits of all the generalized coordinates. | |
| Eigen::VectorXd | getPositionLowerLimits () const override | 
| Get the position lower limits of all the generalized coordinates. | |
| void | setPositionUpperLimit (std::size_t index, double position) override | 
| Set upper limit for position. | |
| double | getPositionUpperLimit (std::size_t index) const override | 
| Get upper limit for position. | |
| void | setPositionUpperLimits (const Eigen::VectorXd &upperLimits) override | 
| Set the position upper limits of all the generalized coordinates. | |
| Eigen::VectorXd | getPositionUpperLimits () const override | 
| Get the position upper limits of all the generalized coordinates. | |
| bool | hasPositionLimit (std::size_t _index) const override | 
| Get whether the position of a generalized coordinate has limits. | |
| void | resetPosition (std::size_t _index) override | 
| Set the position of this generalized coordinate to its initial position. | |
| void | resetPositions () override | 
| Set the positions of all generalized coordinates in this Joint to their initial positions. | |
| void | setInitialPosition (std::size_t _index, double _initial) override | 
| Change the position that resetPositions() will give to this coordinate. | |
| double | getInitialPosition (std::size_t _index) const override | 
| Get the position that resetPosition() will give to this coordinate. | |
| void | setInitialPositions (const Eigen::VectorXd &_initial) override | 
| Change the positions that resetPositions() will give to this Joint's coordinates. | |
| Eigen::VectorXd | getInitialPositions () const override | 
| Get the positions that resetPositions() will give to this Joint's coordinates. | |
| void | setVelocity (std::size_t _index, double _velocity) override | 
| Set the velocity of a single generalized coordinate. | |
| double | getVelocity (std::size_t _index) const override | 
| Get the velocity of a single generalized coordinate. | |
| void | setVelocities (const Eigen::VectorXd &_velocities) override | 
| Set the velocities of all generalized coordinates in this Joint. | |
| Eigen::VectorXd | getVelocities () const override | 
| Get the velocities of all generalized coordinates in this Joint. | |
| void | setVelocityLowerLimit (std::size_t _index, double _velocity) override | 
| Set lower limit for velocity. | |
| double | getVelocityLowerLimit (std::size_t _index) const override | 
| Get lower limit for velocity. | |
| void | setVelocityLowerLimits (const Eigen::VectorXd &lowerLimits) override | 
| Set the velocity lower limits of all the generalized coordinates. | |
| Eigen::VectorXd | getVelocityLowerLimits () const override | 
| Get the velocity lower limits of all the generalized coordinates. | |
| void | setVelocityUpperLimit (std::size_t _index, double _velocity) override | 
| Set upper limit for velocity. | |
| double | getVelocityUpperLimit (std::size_t _index) const override | 
| Get upper limit for velocity. | |
| void | setVelocityUpperLimits (const Eigen::VectorXd &upperLimits) override | 
| Set the velocity upper limits of all the generalized coordinates. | |
| Eigen::VectorXd | getVelocityUpperLimits () const override | 
| Get the velocity upper limits of all the generalized coordinates. | |
| void | resetVelocity (std::size_t _index) override | 
| Set the velocity of a generalized coordinate in this Joint to its initial velocity. | |
| void | resetVelocities () override | 
| Set the velocities of all generalized coordinates in this Joint to their initial velocities. | |
| void | setInitialVelocity (std::size_t _index, double _initial) override | 
| Change the velocity that resetVelocity() will give to this coordinate. | |
| double | getInitialVelocity (std::size_t _index) const override | 
| Get the velocity that resetVelocity() will give to this coordinate. | |
| void | setInitialVelocities (const Eigen::VectorXd &_initial) override | 
| Change the velocities that resetVelocities() will give to this Joint's coordinates. | |
| Eigen::VectorXd | getInitialVelocities () const override | 
| Get the velocities that resetVelocities() will give to this Joint's coordinates. | |
| void | setAcceleration (std::size_t _index, double _acceleration) override | 
| Set the acceleration of a single generalized coordinate. | |
| double | getAcceleration (std::size_t _index) const override | 
| Get the acceleration of a single generalized coordinate. | |
| void | setAccelerations (const Eigen::VectorXd &_accelerations) override | 
| Set the accelerations of all generalized coordinates in this Joint. | |
| Eigen::VectorXd | getAccelerations () const override | 
| Get the accelerations of all generalized coordinates in this Joint. | |
| void | resetAccelerations () override | 
| Set the accelerations of all generalized coordinates in this Joint to zero. | |
| void | setAccelerationLowerLimit (std::size_t _index, double _acceleration) override | 
| Set lower limit for acceleration. | |
| double | getAccelerationLowerLimit (std::size_t _index) const override | 
| Get lower limit for acceleration. | |
| void | setAccelerationLowerLimits (const Eigen::VectorXd &lowerLimits) override | 
| Set the acceleration upper limits of all the generalized coordinates. | |
| Eigen::VectorXd | getAccelerationLowerLimits () const override | 
| Get the acceleration upper limits of all the generalized coordinates. | |
| void | setAccelerationUpperLimit (std::size_t _index, double _acceleration) override | 
| Set upper limit for acceleration. | |
| double | getAccelerationUpperLimit (std::size_t _index) const override | 
| Get upper limit for acceleration. | |
| void | setAccelerationUpperLimits (const Eigen::VectorXd &upperLimits) override | 
| Set the acceleration upper limits of all the generalized coordinates. | |
| Eigen::VectorXd | getAccelerationUpperLimits () const override | 
| Get the acceleration upper limits of all the generalized coordinates. | |
| void | setForce (std::size_t _index, double _force) override | 
| Set the force of a single generalized coordinate. | |
| double | getForce (std::size_t _index) const override | 
| Get the force of a single generalized coordinate. | |
| void | setForces (const Eigen::VectorXd &_forces) override | 
| Set the forces of all generalized coordinates in this Joint. | |
| Eigen::VectorXd | getForces () const override | 
| Get the forces of all generalized coordinates in this Joint. | |
| void | resetForces () override | 
| Set the forces of all generalized coordinates in this Joint to zero. | |
| void | setForceLowerLimit (std::size_t _index, double _force) override | 
| Set lower limit for force. | |
| double | getForceLowerLimit (std::size_t _index) const override | 
| Get lower limit for force. | |
| void | setForceLowerLimits (const Eigen::VectorXd &lowerLimits) override | 
| Set the force upper limits of all the generalized coordinates. | |
| Eigen::VectorXd | getForceLowerLimits () const override | 
| Get the force upper limits of all the generalized coordinates. | |
| void | setForceUpperLimit (std::size_t _index, double _force) override | 
| Set upper limit for force. | |
| double | getForceUpperLimit (std::size_t _index) const override | 
| Get upper limit for force. | |
| void | setForceUpperLimits (const Eigen::VectorXd &upperLimits) override | 
| Set the force upper limits of all the generalized coordinates. | |
| Eigen::VectorXd | getForceUpperLimits () const override | 
| Get the force upper limits of all the generalized coordinates. | |
| void | setVelocityChange (std::size_t _index, double _velocityChange) override | 
| Set a single velocity change. | |
| double | getVelocityChange (std::size_t _index) const override | 
| Get a single velocity change. | |
| void | resetVelocityChanges () override | 
| Set zero all the velocity change. | |
| void | setConstraintImpulse (std::size_t _index, double _impulse) override | 
| Set a single constraint impulse. | |
| double | getConstraintImpulse (std::size_t _index) const override | 
| Get a single constraint impulse. | |
| void | resetConstraintImpulses () override | 
| Set zero all the constraint impulses. | |
| void | integratePositions (double _dt) override | 
| Integrate positions using Euler method. | |
| void | integrateVelocities (double _dt) override | 
| Integrate velocities using Euler method. | |
| 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. | |
| double | computePotentialEnergy () const override | 
| Compute and return the potential energy. | |
| Eigen::Vector6d | getBodyConstraintWrench () const override | 
| Get constraint wrench expressed in body node frame. | |
| bool | hasJointAspect () const | 
| Check if this Composite currently has JointAspect . | |
| Aspect * | getJointAspect () | 
| Get a(an) JointAspect from this Composite. | |
| const Aspect * | getJointAspect () const | 
| Get a(an) JointAspect from this Composite. | |
| Aspect * | getJointAspect (const bool createIfNull) | 
| Get a(an) JointAspect from this Composite. | |
| void | setJointAspect (const Aspect *aspect) | 
| Make a clone of JointAspect and place the clone into this Composite. | |
| void | setJointAspect (std::unique_ptr< Aspect > &&aspect) | 
| Use move semantics to place JointAspect into this Composite. | |
| template<typename... Args> | |
| Aspect * | createJointAspect (Args &&... args) | 
| Construct a(an) JointAspect inside of this Composite. | |
| void | removeJointAspect () | 
| Remove a(an) JointAspect from this Composite. | |
| std::unique_ptr< Aspect > | releaseJointAspect () | 
| Remove a(an) JointAspect from this Composite, but return its unique_ptr instead of letting it be deleted. | |
| void | setProperties (const Properties &properties) | 
| Set the Properties of this Joint. | |
| void | setAspectProperties (const AspectProperties &properties) | 
| Set the AspectProperties of this Joint. | |
| const Properties & | getJointProperties () 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. | |
| const std::string & | setName (const std::string &_name, bool _renameDofs=true) | 
| Set joint name and return the name. | |
| const std::string & | getName () const | 
| Get joint name. | |
| 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 Joint * | getMimicJoint () 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. | |
| bool | isDynamic () const | 
| Return true if this joint is dynamic joint. | |
| BodyNode * | getChildBodyNode () | 
| Get the child BodyNode of this Joint. | |
| const BodyNode * | getChildBodyNode () const | 
| Get the (const) child BodyNode of this Joint. | |
| BodyNode * | getParentBodyNode () | 
| Get the parent BodyNode of this Joint. | |
| const BodyNode * | getParentBodyNode () const | 
| Get the (const) parent BodyNode of this Joint. | |
| SkeletonPtr | getSkeleton () | 
| Get the Skeleton that this Joint belongs to. | |
| std::shared_ptr< const Skeleton > | getSkeleton () const | 
| Get the (const) Skeleton that this Joint belongs to. | |
| 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. | |
| void | setLimitEnforcement (bool enforced) | 
| Sets whether enforcing joint position and velocity limits. | |
| bool | isPositionLimitEnforced () const | 
| Returns whether enforcing joint position limit. | |
| bool | areLimitsEnforced () const | 
| Returns whether enforcing joint position and velocity limits. | |
| 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. | |
| double | getPotentialEnergy () const | 
| Get 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. | |
| Eigen::Vector6d | getWrenchToChildBodyNode (const Frame *withRespectTo=nullptr) const | 
| Get spring force. | |
| Eigen::Vector6d | getWrenchToParentBodyNode (const Frame *withRespectTo=nullptr) const | 
| Returns wrench exerted to the parent body node to satisfy the joint constraint. | |
| virtual std::size_t | incrementVersion () | 
| Increment the version for this object. | |
| virtual std::size_t | getVersion () const | 
| Get the version number of this object. | |
| const AspectProperties & | getAspectProperties () const | 
| Passive forces - spring, viscous friction, Coulomb friction | |
| void | setSpringStiffness (std::size_t _index, double _k) override | 
| Set stiffness of joint spring force. | |
| double | getSpringStiffness (std::size_t _index) const override | 
| Get stiffness of joint spring force. | |
| void | setRestPosition (std::size_t _index, double _q0) override | 
| Set rest position of spring force. | |
| double | getRestPosition (std::size_t _index) const override | 
| Get rest position of spring force. | |
| void | setDampingCoefficient (std::size_t _index, double _d) override | 
| Set coefficient of joint damping (viscous friction) force. | |
| double | getDampingCoefficient (std::size_t _index) const override | 
| Get coefficient of joint damping (viscous friction) force. | |
| void | setCoulombFriction (std::size_t _index, double _friction) override | 
| Set joint Coulomb friction froce. | |
| double | getCoulombFriction (std::size_t _index) const override | 
| Get joint Coulomb friction froce. | |
| Sanity Check | |
| bool | checkSanity (bool _printWarnings=true) const | 
| Returns false if the initial position or initial velocity are outside of limits. | |
| Update Notifiers | |
| 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. | |
| Static Public Member Functions | |
| static const std::string & | getStaticType () | 
| Get joint type for this class. | |
| 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 | |
| WeldJoint (const Properties &properties) | |
| Constructor called by Skeleton class. | |
| Joint * | clone () const override | 
| Create a clone of this Joint. | |
| void | updateRelativeTransform () const override | 
| Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. | |
| void | updateRelativeSpatialVelocity () const override | 
| Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. | |
| void | updateRelativeSpatialAcceleration () const override | 
| Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. | |
| void | updateRelativePrimaryAcceleration () const override | 
| Update J * \( \ddot{q} \) of this joint. | |
| void | updateRelativeJacobian (bool=true) const override | 
| Update spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. | |
| void | updateRelativeJacobianTimeDeriv () const override | 
| Update time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame. | |
| void | registerDofs () override | 
| Called by the Skeleton class. | |
| void | updateDegreeOfFreedomNames () override | 
| Update the names of the joint's degrees of freedom. | |
| DegreeOfFreedom * | createDofPointer (std::size_t _indexInJoint) | 
| Create a DegreeOfFreedom pointer. | |
| void | sendDestructionNotification () const | 
| Send a destruction notification to all Observers. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| void | addVelocityTo (Eigen::Vector6d &_vel) override | 
| Add joint velocity to _vel. | |
| void | setPartialAccelerationTo (Eigen::Vector6d &_partialAcceleration, const Eigen::Vector6d &_childVelocity) override | 
| Set joint partial acceleration to _partialAcceleration. | |
| void | addAccelerationTo (Eigen::Vector6d &_acc) override | 
| Add joint acceleration to _acc. | |
| void | addVelocityChangeTo (Eigen::Vector6d &_velocityChange) override | 
| Add joint velocity change to _velocityChange. | |
| void | addChildArtInertiaTo (Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia) override | 
| Add child's articulated inertia to parent's one. | |
| void | addChildArtInertiaImplicitTo (Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia) override | 
| Add child's articulated inertia to parent's one. Forward dynamics routine. | |
| void | updateInvProjArtInertia (const Eigen::Matrix6d &_artInertia) override | 
| Update inverse of projected articulated body inertia. | |
| void | updateInvProjArtInertiaImplicit (const Eigen::Matrix6d &_artInertia, double _timeStep) override | 
| Forward dynamics routine. | |
| 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. | |
| void | addChildBiasImpulseTo (Eigen::Vector6d &_parentBiasImpulse, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasImpulse) override | 
| Add child's bias impulse to parent's one. | |
| void | updateTotalForce (const Eigen::Vector6d &_bodyForce, double _timeStep) override | 
| Update joint total force. | |
| void | updateTotalImpulse (const Eigen::Vector6d &_bodyImpulse) override | 
| Update joint total impulse. | |
| void | resetTotalImpulses () override | 
| Set total impulses to zero. | |
| void | updateAcceleration (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc) override | 
| Update joint acceleration. | |
| void | updateVelocityChange (const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_velocityChange) override | 
| Update joint velocity change. | |
| void | updateForceID (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override | 
| Update joint force for inverse dynamics. | |
| void | updateForceFD (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override | 
| Update joint force for forward dynamics. | |
| void | updateImpulseID (const Eigen::Vector6d &_bodyImpulse) override | 
| Update joint impulses for inverse dynamics. | |
| void | updateImpulseFD (const Eigen::Vector6d &_bodyImpulse) override | 
| Update joint impulses for forward dynamics. | |
| void | updateConstrainedTerms (double _timeStep) override | 
| Update constrained terms for forward dynamics. | |
| 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. | |
| void | addChildBiasForceForInvAugMassMatrix (Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce) override | 
| Add child's bias force to parent's one. | |
| 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. | |
| 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. | |
| void | updateArticulatedInertia () const | 
| Tells the Skeleton to update the articulated inertia if it needs updating. | |
| Protected Attributes | |
| BodyNode * | mChildBodyNode | 
| 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. | |
| Eigen::Vector6d | mSpatialVelocity | 
| Relative spatial velocity from parent BodyNode to child BodyNode where the velocity is expressed in child body Frame. | |
| Eigen::Vector6d | mSpatialAcceleration | 
| Relative spatial acceleration from parent BodyNode to child BodyNode where the acceleration is expressed in the child body Frame. | |
| Eigen::Vector6d | mPrimaryAcceleration | 
| J * q_dd. | |
| 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. | |
| std::set< Observer * > | mObservers | 
| List of current Observers. | |
| std::size_t | mVersion | 
| AspectProperties | mAspectProperties | 
| Aspect::Properties data, directly accessible to your derived class. | |
| Private Attributes | |
| const std::string | emptyString | 
| Used by getDofName() | |
| VersionCounter * | mDependent | 
| Friends | |
| class | Skeleton | 
class WeldJoint
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | delete | 
| 
 | virtual | 
Destructor.
| 
 | protected | 
Constructor called by Skeleton class.
| 
 | overrideprotectedvirtualinherited | 
Add joint acceleration to _acc.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add child's articulated inertia to parent's one. Forward dynamics routine.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add child's articulated inertia to parent's one.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add child's bias force to parent's one.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add child's bias force to parent's one.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add child's bias force to parent's one.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add child's bias impulse to parent's one.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Implements dart::dynamics::Joint.
| 
 | protectedinherited | 
Add an Observer to the list of Observers.
| 
 | overrideprotectedvirtualinherited | 
Add joint velocity change to _velocityChange.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Add joint velocity to _vel.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Returns whether enforcing joint position and velocity limits.
This enforcement is only enabled when the actuator type is PASSIVE or FORCE.
| 
 | inherited | 
Returns false if the initial position or initial velocity are outside of limits.
| 
 | overrideprotectedvirtual | 
Create a clone of this Joint.
This may only be called by the Skeleton class.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Compute and return the potential energy.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Copy the properties of another Joint.
| 
 | inherited | 
Copy the properties of another Joint.
| 
 | protectedinherited | 
Create a DegreeOfFreedom pointer.
| [in] | _indexInJoint | DegreeOfFreedom'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.
| 
 | inlineinherited | 
Construct a(an) JointAspect inside of this Composite.
| 
 | overridevirtualinherited | 
Get the acceleration of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get lower limit for acceleration.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the acceleration upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the accelerations of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get upper limit for acceleration.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the acceleration upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Get actuator type.
| 
 | inlineinherited | 
| 
 | overridevirtualinherited | 
Get constraint wrench expressed in body node frame.
Implements dart::dynamics::Joint.
| 
 | inherited | 
| 
 | inherited | 
| 
 | overridevirtualinherited | 
Get a single command.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get all commands for this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get a single constraint impulse.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get joint Coulomb friction froce.
| [in] | _index | Index of joint axis. | 
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get coefficient of joint damping (viscous friction) force.
| [in] | _index | Index of joint axis. | 
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Alternative to DegreeOfFreedom::getName()
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the force of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get lower limit for force.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the force upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the forces of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get upper limit for force.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the force upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get a unique index in skeleton of a generalized coordinate in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get a unique index in the kinematic tree of a generalized coordinate in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the position that resetPosition() will give to this coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the positions that resetPositions() will give to this Joint's coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the velocities that resetVelocities() will give to this Joint's coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the velocity that resetVelocity() will give to this coordinate.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Implements dart::dynamics::Joint.
| 
 | inlineinherited | 
Get a(an) JointAspect from this Composite.
| 
 | inlineinherited | 
Get a(an) JointAspect from this Composite.
| 
 | 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. 
 
| 
 | inherited | 
| 
 | inherited | 
Get the index of this Joint within its tree.
| 
 | inherited | 
Get the Properties of this Joint.
| 
 | inherited | 
Deprecated. Use getRelativeJacobian() instead.
| 
 | inherited | 
Deprecated. Use getRelativeJacobian() instead.
| 
 | inherited | 
Deprecated. Use getRelativeJacobianTimeDeriv() instead.
| 
 | inherited | 
Deprecated. Use getLocalPrimaryAcceleration() instead.
| 
 | inherited | 
Deprecated. Use getLocalSpatialAcceleration() instead.
| 
 | inherited | 
Deprecated. Use getLocalSpatialVelocity() instead.
| 
 | inherited | 
Deprecated. Use getRelativeTransform() instead.
| 
 | inherited | 
Get mimic joint.
| 
 | inherited | 
Get mimic joint multiplier.
| 
 | inherited | 
Get mimic joint offset.
| 
 | inherited | 
Get joint name.
| 
 | overridevirtualinherited | 
Get number of generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | inherited | 
| 
 | inherited | 
| 
 | overridevirtualinherited | 
Get the position of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Return the difference of two generalized coordinates which are measured in the configuration space of this Skeleton.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get lower limit for position.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the position lower limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the positions of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get upper limit for position.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the position upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Get potential energy.
| 
 | overrideprotectedvirtualinherited | 
Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
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.
| 
 | inherited | 
Get J * \( \ddot{q} \) of this joint.
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
| 
 | overridevirtualinherited | 
Get rest position of spring force.
| [in] | _index | Index of joint axis. | 
Implements dart::dynamics::Joint.
| 
 | inherited | 
| 
 | inherited | 
| 
 | overrideprotectedvirtualinherited | 
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get stiffness of joint spring force.
| [in] | _index | Index of joint axis. | 
Implements dart::dynamics::Joint.
| 
 | static | 
Get joint type for this class.
| 
 | inherited | 
Get transformation from child body node to this joint.
| 
 | inherited | 
Get transformation from parent body node to this joint.
| 
 | inherited | 
Get the index of the tree that this Joint belongs to.
| 
 | overridevirtual | 
Gets a string representing the joint type.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the velocities of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the velocity of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get a single velocity change.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get lower limit for velocity.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the velocity lower limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get upper limit for velocity.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Get the velocity upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | virtualinherited | 
Get the version number of this object.
| WeldJoint::Properties dart::dynamics::WeldJoint::getWeldJointProperties | ( | ) | const | 
Get the Properties of this WeldJoint.
| 
 | inherited | 
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.
| [in] | _timeStep | Time 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.
| [in] | withRespectTo | The reference frame where the wrench is measured. The default (i.e., nullptr) is to get the wrench measured in the joint frame. | 
| 
 | inherited | 
Returns wrench exerted to the parent body node to satisfy the joint constraint.
| [in] | withRespectTo | The reference frame where the wrench is measured. The default (i.e., nullptr) is to get the wrench measured in the joint frame. | 
| 
 | inherited | 
Get the Properties of this ZeroDofJoint.
| 
 | inlineinherited | 
Check if this Composite currently has JointAspect .
| 
 | overridevirtualinherited | 
Get whether the position of a generalized coordinate has limits.
Implements dart::dynamics::Joint.
| 
 | virtualinherited | 
Increment the version for this object.
Reimplemented in dart::dynamics::Shape.
| 
 | overridevirtualinherited | 
Integrate positions using Euler method.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Integrate velocities using Euler method.
Implements dart::dynamics::Joint.
| 
 | overridevirtual | 
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.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Alternative to DegreeOfFreedom::isNamePreserved()
Implements dart::dynamics::Joint.
| 
 | inherited | 
Return true if this joint is dynamic joint.
| 
 | 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.
| 
 | inherited | 
Returns whether enforcing joint position limit.
This enforcement is only enabled when the actuator type is PASSIVE or FORCE.
| 
 | inherited | 
Notify that an acceleration has updated.
| 
 | inherited | 
Notify that an acceleration has updated.
| 
 | inherited | 
Notify that a position has updated.
| 
 | inherited | 
Notify that a position has updated.
| 
 | inherited | 
Notify that a velocity has updated.
| 
 | inherited | 
Notify that a velocity has updated.
| 
 | overridevirtualinherited | 
Alternative to DegreeOfFreedom::preserveName()
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Called by the Skeleton class.
Implements dart::dynamics::Joint.
| 
 | 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. 
 
| 
 | inlineinherited | 
Remove a(an) JointAspect from this Composite.
| 
 | protectedinherited | 
Remove an Observer from the list of Observers.
| 
 | overridevirtualinherited | 
Set the accelerations of all generalized coordinates in this Joint to zero.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set all the commands for this Joint to zero.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set zero all the constraint impulses.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the forces of all generalized coordinates in this Joint to zero.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the position of this generalized coordinate to its initial position.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the positions of all generalized coordinates in this Joint to their initial positions.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Set total impulses to zero.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the velocities of all generalized coordinates in this Joint to their initial velocities.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the velocity of a generalized coordinate in this Joint to its initial velocity.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set zero all the velocity change.
Implements dart::dynamics::Joint.
| 
 | 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.
| 
 | overridevirtualinherited | 
Set the acceleration of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set lower limit for acceleration.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the acceleration upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the accelerations of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set upper limit for acceleration.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the acceleration upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Set actuator type.
| 
 | inherited | 
Set the AspectProperties of this Joint.
| 
 | overridevirtualinherited | 
Set a single command.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set all commands for this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set a single constraint impulse.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set joint Coulomb friction froce.
| [in] | _index | Index of joint axis. | 
| [in] | _friction | Joint Coulomb friction froce given index. | 
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set coefficient of joint damping (viscous friction) force.
| [in] | _index | Index of joint axis. | 
| [in] | _coeff | Damping coefficient. | 
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Alternative to DegreeOfFreedom::setName()
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the force of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set lower limit for force.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the force upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the forces of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set upper limit for force.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the force upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Change the position that resetPositions() will give to this coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Change the positions that resetPositions() will give to this Joint's coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Change the velocities that resetVelocities() will give to this Joint's coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Change the velocity that resetVelocity() will give to this coordinate.
Implements dart::dynamics::Joint.
| 
 | 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. 
 
| 
 | 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. 
 
| 
 | inherited | 
Sets whether enforcing joint position and velocity limits.
This enforcement is only enabled when the actuator type is PASSIVE or FORCE.
| 
 | inherited | 
Set mimic joint.
| 
 | inherited | 
Set joint name and return the name.
| [in] | _name | The specified joint name to be set. | 
| [in] | _renameDofs | If 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.
| 
 | overrideprotectedvirtualinherited | 
Set joint partial acceleration to _partialAcceleration.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the position of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Sets whether enforcing joint position and velocity limits.
The joint position limit is valid when the actuator type is one of PASSIVE/FORCE.
| 
 | overridevirtualinherited | 
Set lower limit for position.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the position lower limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the positions of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set upper limit for position.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the position upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | inherited | 
Set the Properties of this Joint.
| 
 | overridevirtualinherited | 
Set rest position of spring force.
| [in] | _index | Index of joint axis. | 
| [in] | _q0 | Rest position. | 
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set stiffness of joint spring force.
| [in] | _index | Index of joint axis. | 
| [in] | _k | Spring stiffness. | 
Implements dart::dynamics::Joint.
| 
 | overridevirtual | 
Set transformation from child body node to this joint.
Reimplemented from dart::dynamics::Joint.
| 
 | overridevirtual | 
Set transformation from parent body node to this joint.
Reimplemented from dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the velocities of all generalized coordinates in this Joint.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the velocity of a single generalized coordinate.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set a single velocity change.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set lower limit for velocity.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the velocity lower limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set upper limit for velocity.
Implements dart::dynamics::Joint.
| 
 | overridevirtualinherited | 
Set the velocity upper limits of all the generalized coordinates.
Implements dart::dynamics::Joint.
| 
 | protectedinherited | 
| 
 | overrideprotectedvirtualinherited | 
Update joint acceleration.
Implements dart::dynamics::Joint.
| 
 | protectedinherited | 
Tells the Skeleton to update the articulated inertia if it needs updating.
| 
 | overrideprotectedvirtualinherited | 
Update constrained terms for forward dynamics.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update the names of the joint's degrees of freedom.
Used when setName() is called with _renameDofs set to true.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint force for forward dynamics.
| [in] | _bodyForce | Transmitting 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 | 
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint force for inverse dynamics.
| [in] | _bodyForce | Transmitting 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 | 
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint impulses for forward dynamics.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint impulses for inverse dynamics.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update inverse of projected articulated body inertia.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Forward dynamics routine.
Implements dart::dynamics::Joint.
| 
 | protectedinherited | 
Deprecated. Use updateRelativeJacobian() instead.
| 
 | protectedinherited | 
Deprecated. Use updateRelativeJacobianTimeDeriv() instead.
| 
 | protectedinherited | 
Deprecated. Use updateRelativePrimaryAcceleration() instead.
| 
 | protectedinherited | 
Deprecated. Use updateRelativeSpatialAcceleration() instead.
| 
 | protectedinherited | 
Deprecated. Use updateRelativeSpatialVelocity() instead.
| 
 | protectedinherited | 
Deprecated. Use updateRelativeTransform() instead.
| 
 | overrideprotectedvirtual | 
Update spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
| [in] | mandatory | This 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. | 
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtual | 
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.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtual | 
Update J * \( \ddot{q} \) of this joint.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtual | 
Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtual | 
Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtual | 
Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode frame.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint total force.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint total impulse.
Implements dart::dynamics::Joint.
| 
 | overrideprotectedvirtualinherited | 
Update joint velocity change.
| _artInertia | |
| _velocityChange | 
Implements dart::dynamics::Joint.
| 
 | friend | 
| 
 | staticconstexprinherited | 
| 
 | staticinherited | 
Default actuator type.
| 
 | privateinherited | 
Used by getDofName()
| 
 | staticconstexprinherited | 
| 
 | staticconstexprinherited | 
| 
 | protectedinherited | 
Aspect::Properties data, directly accessible to your derived class.
| 
 | protectedinherited | 
| 
 | privateinherited | 
| 
 | staticconstexprinherited | 
| 
 | mutableprotectedinherited | 
True iff this joint's relative Jacobian has not been updated since the last position change.
| 
 | mutableprotectedinherited | 
True iff this joint's relative Jacobian time derivative has not been updated since the last position or velocity change.
| 
 | mutableprotectedinherited | 
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativePrimaryAcceleration()
| 
 | mutableprotectedinherited | 
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelativeSpatialAcceleration()
| 
 | mutableprotectedinherited | 
True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVelocity()
| 
 | mutableprotectedinherited | 
True iff this joint's position has changed since the last call to getRelativeTransform()
| 
 | mutableprotectedinherited | 
List of current Observers.
| 
 | mutableprotectedinherited | 
J * q_dd.
Do not use directly! Use getRelativePrimaryAcceleration() to access this
| 
 | 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
| 
 | 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
| 
 | 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
| 
 | protectedinherited | 
| 
 | staticconstexprinherited | 
| 
 | staticconstexprinherited | 
| 
 | staticconstexprinherited |