dart
Classes | Public Member Functions | Protected Member Functions | List of all members
dart::dynamics::ZeroDofJoint Class Reference

class ZeroDofJoint More...

#include <ZeroDofJoint.hpp>

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

Classes

struct  Properties
 

Public Member Functions

 ZeroDofJoint (const ZeroDofJoint &)=delete
 
virtual ~ZeroDofJoint ()
 Destructor.
 
Properties getZeroDofJointProperties () const
 Get the Properties of this ZeroDofJoint.
 
DegreeOfFreedomgetDof (std::size_t) override
 Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
 
const DegreeOfFreedomgetDof (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. More...
 
double computePotentialEnergy () const override
 Compute and return the potential energy.
 
Eigen::Vector6d getBodyConstraintWrench () const override
 Get constraint wrench expressed in body node frame.
 
Passive forces - spring, viscous friction, Coulomb friction
void setSpringStiffness (std::size_t _index, double _k) override
 Set stiffness of joint spring force. More...
 
double getSpringStiffness (std::size_t _index) const override
 Get stiffness of joint spring force. More...
 
void setRestPosition (std::size_t _index, double _q0) override
 Set rest position of spring force. More...
 
double getRestPosition (std::size_t _index) const override
 Get rest position of spring force. More...
 
void setDampingCoefficient (std::size_t _index, double _d) override
 Set coefficient of joint damping (viscous friction) force. More...
 
double getDampingCoefficient (std::size_t _index) const override
 Get coefficient of joint damping (viscous friction) force. More...
 
void setCoulombFriction (std::size_t _index, double _friction) override
 Set joint Coulomb friction froce. More...
 
double getCoulombFriction (std::size_t _index) const override
 Get joint Coulomb friction froce. More...
 
- Public Member Functions inherited from dart::dynamics::Joint
 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...
 
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.
 
virtual bool isCyclic (std::size_t _index) const =0
 Get whether a generalized coordinate is cyclic. More...
 
bool checkSanity (bool _printWarnings=true) const
 Returns false if the initial position or initial velocity are outside of limits.
 
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
 

Protected Member Functions

 ZeroDofJoint ()
 Constructor called by inheriting classes.
 
void registerDofs () override
 Called by the Skeleton class.
 
void updateDegreeOfFreedomNames () override
 Update the names of the joint's degrees of freedom. More...
 
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. More...
 
void updateForceID (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override
 Update joint force for inverse dynamics. More...
 
void updateForceFD (const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override
 Update joint force for forward dynamics. More...
 
void updateImpulseID (const Eigen::Vector6d &_bodyImpulse) override
 Update joint impulses for inverse dynamics.
 
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
 
- Protected Member Functions inherited from dart::dynamics::Joint
 Joint ()
 Constructor called by inheriting class.
 
virtual Jointclone () const =0
 Create a clone of this Joint. More...
 
DegreeOfFreedomcreateDofPointer (std::size_t _indexInJoint)
 Create a DegreeOfFreedom pointer. More...
 
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.
 
- 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)
 

Additional Inherited Members

- Public Types inherited from dart::dynamics::Joint
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 >
 
- Static Public Attributes inherited from dart::dynamics::Joint
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 Attributes inherited from dart::dynamics::Joint
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.
 

Detailed Description

class ZeroDofJoint

Member Function Documentation

◆ getCoulombFriction()

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

Get joint Coulomb friction froce.

Parameters
[in]_indexIndex of joint axis.

Implements dart::dynamics::Joint.

◆ getDampingCoefficient()

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

Get coefficient of joint damping (viscous friction) force.

Parameters
[in]_indexIndex of joint axis.

Implements dart::dynamics::Joint.

◆ getPositionDifferences()

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

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

Implements dart::dynamics::Joint.

◆ getRestPosition()

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

Get rest position of spring force.

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

Implements dart::dynamics::Joint.

◆ getSpringStiffness()

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

Get stiffness of joint spring force.

Parameters
[in]_indexIndex of joint axis.

Implements dart::dynamics::Joint.

◆ setCoulombFriction()

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

Set joint Coulomb friction froce.

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

Implements dart::dynamics::Joint.

◆ setDampingCoefficient()

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

Set coefficient of joint damping (viscous friction) force.

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

Implements dart::dynamics::Joint.

◆ setRestPosition()

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

Set rest position of spring force.

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

Implements dart::dynamics::Joint.

◆ setSpringStiffness()

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

Set stiffness of joint spring force.

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

Implements dart::dynamics::Joint.

◆ updateDegreeOfFreedomNames()

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

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

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

Implements dart::dynamics::Joint.

◆ updateForceFD()

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

Update joint force for forward dynamics.

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

Implements dart::dynamics::Joint.

◆ updateForceID()

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

Update joint force for inverse dynamics.

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

Implements dart::dynamics::Joint.

◆ updateVelocityChange()

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

Update joint velocity change.

Parameters
_artInertia
_velocityChange

Implements dart::dynamics::Joint.


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