33#ifndef DART_DYNAMICS_JOINT_HPP_
34#define DART_DYNAMICS_JOINT_HPP_
124 const std::string&
setName(
const std::string& _name,
125 bool _renameDofs =
true);
128 const std::string&
getName()
const;
131 virtual const std::string&
getType()
const = 0;
140 void setMimicJoint(
const Joint* _mimicJoint,
double _mimicMultiplier = 1.0,
double _mimicOffset = 0.0);
178 std::shared_ptr<const Skeleton>
getSkeleton()
const;
234 const std::string& _name,
235 bool _preserveName=
true) = 0;
244 virtual const std::string&
getDofName(std::size_t _index)
const = 0;
254 virtual void setCommand(std::size_t _index,
double _command) = 0;
275 virtual void setPosition(std::size_t _index,
double _position) = 0;
315 virtual bool isCyclic(std::size_t _index)
const = 0;
348 virtual void setVelocity(std::size_t _index,
double _velocity) = 0;
457 virtual void setForce(std::size_t _index,
double _force) = 0;
460 virtual double getForce(std::size_t _index)
const = 0;
463 virtual void setForces(
const Eigen::VectorXd& _forces) = 0;
504 bool checkSanity(
bool _printWarnings =
true)
const;
549 const Eigen::VectorXd& _q2,
const Eigen::VectorXd& _q1)
const = 0;
657 const
Eigen::VectorXd& positions) const = 0;
823 Eigen::Vector6d& _partialAcceleration,
824 const
Eigen::Vector6d& _childVelocity) = 0;
835 Eigen::Matrix6d& _parentArtInertia,
836 const
Eigen::Matrix6d& _childArtInertia) = 0;
840 Eigen::Matrix6d& _parentArtInertiaImplicit,
841 const
Eigen::Matrix6d& _childArtInertiaImplicit) = 0;
849 const
Eigen::Matrix6d& _artInertia,
850 double _timeStep) = 0;
855 Eigen::Vector6d& _parentBiasForce,
856 const
Eigen::Matrix6d& _childArtInertia,
857 const
Eigen::Vector6d& _childBiasForce,
858 const
Eigen::Vector6d& _childPartialAcc) = 0;
862 Eigen::Vector6d& _parentBiasImpulse,
863 const
Eigen::Matrix6d& _childArtInertia,
864 const
Eigen::Vector6d& _childBiasImpulse) = 0;
868 double _timeStep) = 0;
880 const
Eigen::Vector6d& _spatialAcc) = 0;
886 const
Eigen::Matrix6d& _artInertia,
887 const
Eigen::Vector6d& _velocityChange) = 0;
895 bool _withDampingForces,
896 bool _withSpringForces) = 0;
904 bool _withDampingForcese,
905 bool _withSpringForces) = 0;
924 Eigen::Vector6d& _parentBiasForce,
925 const
Eigen::Matrix6d& _childArtInertia,
926 const
Eigen::Vector6d& _childBiasForce) = 0;
930 Eigen::Vector6d& _parentBiasForce,
931 const
Eigen::Matrix6d& _childArtInertia,
932 const
Eigen::Vector6d& _childBiasForce) = 0;
936 const
Eigen::Vector6d& _bodyForce) = 0;
940 const
std::
size_t _col,
941 const
Eigen::Matrix6d& _artInertia,
942 const
Eigen::Vector6d& _spatialAcc) = 0;
946 const
std::
size_t _col,
947 const
Eigen::Matrix6d& _artInertia,
948 const
Eigen::Vector6d& _spatialAcc) = 0;
955 const
Eigen::Vector6d& _spatial) = 0;
1018 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
BodyPropPtr properties
Definition SdfParser.cpp:80
detail::CompositeProperties Properties
Definition Composite.hpp:56
Inherit this class to embed Properties into your Composite object.
Definition EmbeddedAspect.hpp:210
typename Aspect::Properties AspectProperties
Definition EmbeddedAspect.hpp:215
This is the implementation of a standard embedded-properties Aspect.
Definition EmbeddedAspect.hpp:169
The Subject class is a base class for any object that wants to report when it gets destroyed.
Definition Subject.hpp:58
VersionCounter is an interface for objects that count their versions.
Definition VersionCounter.hpp:43
Definition CompositeData.hpp:104
BodyNode class represents a single node of the skeleton.
Definition BodyNode.hpp:78
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition DegreeOfFreedom.hpp:53
class Joint
Definition Joint.hpp:59
virtual void updateInvProjArtInertia(const Eigen::Matrix6d &_artInertia)=0
Update inverse of projected articulated body inertia.
virtual const std::string & getType() const =0
Gets a string representing the joint type.
bool mNeedSpatialAccelerationUpdate
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelat...
Definition Joint.hpp:999
virtual double getVelocityLowerLimit(std::size_t _index) const =0
Get lower limit for velocity.
virtual void updateForceID(const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces)=0
Update joint force for inverse dynamics.
virtual void updateTotalForceForInvMassMatrix(const Eigen::Vector6d &_bodyForce)=0
virtual double getDampingCoefficient(std::size_t _index) const =0
Get coefficient of joint damping (viscous friction) force.
virtual double getInitialPosition(std::size_t _index) const =0
Get the position that resetPosition() will give to this coordinate.
virtual void setTransformFromChildBodyNode(const Eigen::Isometry3d &_T)
Set transformation from child body node to this joint.
Definition Joint.cpp:483
virtual void updateImpulseFD(const Eigen::Vector6d &_bodyImpulse)=0
Update joint impulses for forward dynamics.
virtual Eigen::VectorXd getForces() const =0
Get the forces of all generalized coordinates in this Joint.
virtual Eigen::VectorXd getSpatialToGeneralized(const Eigen::Vector6d &_spatial)=0
virtual void updateTotalImpulse(const Eigen::Vector6d &_bodyImpulse)=0
Update joint total impulse.
virtual double getVelocityUpperLimit(std::size_t _index) const =0
Get upper limit for velocity.
void setActuatorType(ActuatorType _actuatorType)
Set actuator type.
Definition Joint.cpp:194
virtual void updateForceFD(const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForcese, bool _withSpringForces)=0
Update joint force for forward dynamics.
Eigen::Vector6d mPrimaryAcceleration
J * q_dd.
Definition Joint.hpp:985
virtual double getAccelerationUpperLimit(std::size_t _index) const =0
Get upper limit for acceleration.
virtual void addChildBiasForceForInvMassMatrix(Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
Add child's bias force to parent's one.
virtual void setPositions(const Eigen::VectorXd &_positions)=0
Set the positions of all generalized coordinates in this Joint.
virtual void resetPosition(std::size_t _index)=0
Set the position of this generalized coordinate to its initial position.
virtual void setForceUpperLimit(std::size_t _index, double _force)=0
Set upper limit for force.
virtual void resetConstraintImpulses()=0
Set zero all the constraint impulses.
virtual std::size_t getNumDofs() const =0
Get number of generalized coordinates.
virtual void setCommand(std::size_t _index, double _command)=0
Set a single command.
const Eigen::Vector6d & getRelativePrimaryAcceleration() const
Get J * \ddot{q} of this joint.
Definition Joint.cpp:377
detail::ActuatorType ActuatorType
Definition Joint.hpp:65
virtual void resetAccelerations()=0
Set the accelerations of all generalized coordinates in this Joint to zero.
virtual double getForceUpperLimit(std::size_t _index) const =0
Get upper limit for force.
virtual void setInitialVelocity(std::size_t _index, double _initial)=0
Change the velocity that resetVelocity() will give to this coordinate.
virtual void updateInvProjArtInertiaImplicit(const Eigen::Matrix6d &_artInertia, double _timeStep)=0
Forward dynamics routine.
virtual void updateRelativeJacobianTimeDeriv() const =0
Update time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expr...
virtual void updateRelativeJacobian(bool mandatory=true) const =0
Update spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child ...
const Eigen::Vector6d & getLocalSpatialVelocity() const
Deprecated. Use getLocalSpatialVelocity() instead.
Definition Joint.cpp:305
bool mNeedPrimaryAccelerationUpdate
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelat...
Definition Joint.hpp:1004
virtual Eigen::VectorXd getPositionUpperLimits() const =0
Get the position upper limits of all the generalized coordinates.
virtual double getConstraintImpulse(std::size_t _index) const =0
Get a single constraint impulse.
virtual void updateDegreeOfFreedomNames()=0
Update the names of the joint's degrees of freedom.
static constexpr ActuatorType PASSIVE
Definition Joint.hpp:67
virtual void setVelocity(std::size_t _index, double _velocity)=0
Set the velocity of a single generalized coordinate.
virtual double computePotentialEnergy() const =0
Compute and return the potential energy.
virtual void setForces(const Eigen::VectorXd &_forces)=0
Set the forces of all generalized coordinates in this Joint.
virtual void getInvAugMassMatrixSegment(Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
std::size_t getJointIndexInSkeleton() const
Get the index of this Joint within its Skeleton.
Definition Joint.cpp:401
virtual double getForceLowerLimit(std::size_t _index) const =0
Get lower limit for force.
virtual void setInitialVelocities(const Eigen::VectorXd &_initial)=0
Change the velocities that resetVelocities() will give to this Joint's coordinates.
virtual void resetVelocityChanges()=0
Set zero all the velocity change.
virtual void setAccelerationLowerLimit(std::size_t _index, double _acceleration)=0
Set lower limit for acceleration.
const std::string & getName() const
Get joint name.
Definition Joint.cpp:188
const Eigen::Vector6d & getLocalSpatialAcceleration() const
Deprecated. Use getLocalSpatialAcceleration() instead.
Definition Joint.cpp:311
bool mNeedSpatialVelocityUpdate
True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVeloc...
Definition Joint.hpp:994
bool checkSanity(bool _printWarnings=true) const
Returns false if the initial position or initial velocity are outside of limits.
Definition Joint.cpp:419
const Eigen::Isometry3d & getLocalTransform() const
Deprecated. Use getRelativeTransform() instead.
Definition Joint.cpp:299
virtual void setVelocityUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the velocity upper limits of all the generalized coordinates.
static constexpr ActuatorType SERVO
Definition Joint.hpp:68
virtual void integratePositions(double _dt)=0
Integrate positions using Euler method.
virtual void setForceUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the force upper limits of all the generalized coordinates.
virtual double getVelocityChange(std::size_t _index) const =0
Get a single velocity change.
virtual Eigen::VectorXd getPositionDifferences(const Eigen::VectorXd &_q2, const Eigen::VectorXd &_q1) const =0
Return the difference of two generalized coordinates which are measured in the configuration space of...
BodyNode * getParentBodyNode()
Get the parent BodyNode of this Joint.
Definition Joint.cpp:272
virtual double getSpringStiffness(std::size_t _index) const =0
Get stiffness of joint spring force.
static constexpr ActuatorType ACCELERATION
Definition Joint.hpp:70
Eigen::Vector6d mSpatialAcceleration
Relative spatial acceleration from parent BodyNode to child BodyNode where the acceleration is expres...
Definition Joint.hpp:980
virtual void updateVelocityChange(const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_velocityChange)=0
Update joint velocity change.
virtual void addChildBiasImpulseTo(Eigen::Vector6d &_parentBiasImpulse, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasImpulse)=0
Add child's bias impulse to parent's one.
virtual void resetForces()=0
Set the forces of all generalized coordinates in this Joint to zero.
virtual void setTransformFromParentBodyNode(const Eigen::Isometry3d &_T)
Set transformation from parent body node to this joint.
Definition Joint.cpp:475
virtual double getVelocity(std::size_t _index) const =0
Get the velocity of a single generalized coordinate.
virtual double getAcceleration(std::size_t _index) const =0
Get the acceleration of a single generalized coordinate.
virtual void updateRelativeSpatialVelocity() const =0
Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child ...
void updateArticulatedInertia() const
Tells the Skeleton to update the articulated inertia if it needs updating.
Definition Joint.cpp:563
bool mNeedTransformUpdate
True iff this joint's position has changed since the last call to getRelativeTransform()
Definition Joint.hpp:989
detail::JointProperties Properties
Definition Joint.hpp:63
DegreeOfFreedom * createDofPointer(std::size_t _indexInJoint)
Create a DegreeOfFreedom pointer.
Definition Joint.cpp:521
void updateLocalSpatialVelocity() const
Deprecated. Use updateRelativeSpatialVelocity() instead.
Definition Joint.cpp:533
void notifyAccelerationUpdate()
Notify that an acceleration has updated.
Definition Joint.cpp:652
static constexpr ActuatorType LOCKED
Definition Joint.hpp:72
virtual double getCommand(std::size_t _index) const =0
Get a single command.
void notifyVelocityUpdated()
Notify that a velocity has updated.
Definition Joint.cpp:637
void copy(const Joint &_otherJoint)
Copy the properties of another Joint.
Definition Joint.cpp:133
Eigen::Vector6d mSpatialVelocity
Relative spatial velocity from parent BodyNode to child BodyNode where the velocity is expressed in c...
Definition Joint.hpp:974
void notifyPositionUpdate()
Notify that a position has updated.
Definition Joint.cpp:597
virtual void setPositionLowerLimit(std::size_t _index, double _position)=0
Set lower limit for position.
virtual void addAccelerationTo(Eigen::Vector6d &_acc)=0
Add joint acceleration to _acc.
virtual Joint * clone() const =0
Create a clone of this Joint.
virtual void preserveDofName(std::size_t _index, bool _preserve)=0
Alternative to DegreeOfFreedom::preserveName()
virtual Eigen::VectorXd getVelocityUpperLimits() const =0
Get the velocity upper limits of all the generalized coordinates.
virtual void setInitialPosition(std::size_t _index, double _initial)=0
Change the position that resetPositions() will give to this coordinate.
virtual Eigen::VectorXd getInitialVelocities() const =0
Get the velocities that resetVelocities() will give to this Joint's coordinates.
const std::string & setName(const std::string &_name, bool _renameDofs=true)
Set joint name and return the name.
Definition Joint.cpp:158
virtual Eigen::VectorXd getVelocityLowerLimits() const =0
Get the velocity lower limits of all the generalized coordinates.
virtual Eigen::VectorXd getInitialPositions() const =0
Get the positions that resetPositions() will give to this Joint's coordinates.
virtual void resetPositions()=0
Set the positions of all generalized coordinates in this Joint to their initial positions.
BodyNode * mChildBodyNode
Child BodyNode pointer that this Joint belongs to.
Definition Joint.hpp:962
bool isKinematic() const
Return true if this joint is kinematic joint.
Definition Joint.cpp:232
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this Joint.
Definition Joint.cpp:116
const Properties & getJointProperties() const
Get the Properties of this Joint.
Definition Joint.cpp:127
virtual std::size_t getIndexInTree(std::size_t _index) const =0
Get a unique index in the kinematic tree of a generalized coordinate in this Joint.
virtual void setConstraintImpulse(std::size_t _index, double _impulse)=0
Set a single constraint impulse.
virtual Eigen::VectorXd getCommands() const =0
Get all commands for this Joint.
virtual void setForce(std::size_t _index, double _force)=0
Set the force of a single generalized coordinate.
ActuatorType getActuatorType() const
Get actuator type.
Definition Joint.cpp:200
virtual double getRestPosition(std::size_t _index) const =0
Get rest position of spring force.
virtual bool hasPositionLimit(std::size_t _index) const =0
Get whether the position of a generalized coordinate has limits.
const Eigen::Isometry3d & getRelativeTransform() const
Get transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode f...
Definition Joint.cpp:341
virtual void setAccelerations(const Eigen::VectorXd &_accelerations)=0
Set the accelerations of all generalized coordinates in this Joint.
virtual void addInvMassMatrixSegmentTo(Eigen::Vector6d &_acc)=0
virtual void setVelocityLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the velocity lower limits of all the generalized coordinates.
virtual const std::string & getDofName(std::size_t _index) const =0
Alternative to DegreeOfFreedom::getName()
virtual const DegreeOfFreedom * getDof(std::size_t _index) const =0
Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
const Eigen::Vector6d & getRelativeSpatialAcceleration() const
Get spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child...
Definition Joint.cpp:365
void notifyVelocityUpdate()
Notify that a velocity has updated.
Definition Joint.cpp:631
virtual void updateRelativePrimaryAcceleration() const =0
Update J * \ddot{q} of this joint.
virtual void setPositionUpperLimit(std::size_t _index, double _position)=0
Set upper limit for position.
virtual void resetVelocities()=0
Set the velocities of all generalized coordinates in this Joint to their initial velocities.
virtual double getAccelerationLowerLimit(std::size_t _index) const =0
Get lower limit for acceleration.
virtual void setForceLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the force upper limits of all the generalized coordinates.
virtual Eigen::VectorXd getAccelerations() const =0
Get the accelerations of all generalized coordinates in this Joint.
virtual void setDampingCoefficient(std::size_t _index, double _coeff)=0
Set coefficient of joint damping (viscous friction) force.
virtual void setVelocityChange(std::size_t _index, double _velocityChange)=0
Set a single velocity change.
virtual void resetVelocity(std::size_t _index)=0
Set the velocity of a generalized coordinate in this Joint to its initial velocity.
virtual void setSpringStiffness(std::size_t _index, double _k)=0
Set stiffness of joint spring force.
SkeletonPtr getSkeleton()
Get the Skeleton that this Joint belongs to.
Definition Joint.cpp:287
static constexpr ActuatorType FORCE
Definition Joint.hpp:66
virtual void setAcceleration(std::size_t _index, double _acceleration)=0
Set the acceleration of a single generalized coordinate.
void updateLocalSpatialAcceleration() const
Deprecated. Use updateRelativeSpatialAcceleration() instead.
Definition Joint.cpp:539
virtual void registerDofs()=0
Called by the Skeleton class.
virtual Eigen::VectorXd getForceLowerLimits() const =0
Get the force upper limits of all the generalized coordinates.
virtual void setRestPosition(std::size_t _index, double _q0)=0
Set rest position of spring force.
virtual void getInvMassMatrixSegment(Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
Joint(const Joint &)=delete
const Joint * getMimicJoint() const
Get mimic joint.
Definition Joint.cpp:214
void notifyAccelerationUpdated()
Notify that an acceleration has updated.
Definition Joint.cpp:658
Joint & operator=(const Joint &_otherJoint)
Same as copy(const Joint&)
Definition Joint.cpp:151
virtual void setPositionUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the position upper limits of all the generalized coordinates.
virtual void addChildArtInertiaImplicitTo(Eigen::Matrix6d &_parentArtInertiaImplicit, const Eigen::Matrix6d &_childArtInertiaImplicit)=0
Add child's articulated inertia to parent's one. Forward dynamics routine.
virtual void setPositionLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the position lower limits of all the generalized coordinates.
virtual void setAccelerationLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the acceleration upper limits of all the generalized coordinates.
bool isPositionLimitEnforced() const
Get whether enforcing joint position limit.
Definition Joint.cpp:395
static const ActuatorType DefaultActuatorType
Default actuator type.
Definition Joint.hpp:93
virtual void setForceLowerLimit(std::size_t _index, double _force)=0
Set lower limit for force.
virtual double getForce(std::size_t _index) const =0
Get the force of a single generalized coordinate.
virtual const std::string & setDofName(std::size_t _index, const std::string &_name, bool _preserveName=true)=0
Alternative to DegreeOfFreedom::setName()
virtual void setVelocities(const Eigen::VectorXd &_velocities)=0
Set the velocities of all generalized coordinates in this Joint.
std::size_t getTreeIndex() const
Get the index of the tree that this Joint belongs to.
Definition Joint.cpp:413
void updateLocalPrimaryAcceleration() const
Deprecated. Use updateRelativePrimaryAcceleration() instead.
Definition Joint.cpp:545
virtual Eigen::VectorXd getForceUpperLimits() const =0
Get the force upper limits of all the generalized coordinates.
virtual Eigen::VectorXd getAccelerationLowerLimits() const =0
Get the acceleration upper limits of all the generalized coordinates.
virtual void updateConstrainedTerms(double _timeStep)=0
Update constrained terms for forward dynamics.
void updateLocalTransform() const
Deprecated. Use updateRelativeTransform() instead.
Definition Joint.cpp:527
void notifyPositionUpdated()
Notify that a position has updated.
Definition Joint.cpp:603
virtual double getInitialVelocity(std::size_t _index) const =0
Get the velocity that resetVelocity() will give to this coordinate.
virtual void resetCommands()=0
Set all the commands for this Joint to zero.
virtual void addVelocityChangeTo(Eigen::Vector6d &_velocityChange)=0
Add joint velocity change to _velocityChange.
virtual const math::Jacobian getRelativeJacobianTimeDeriv() const =0
Get time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode express...
const Eigen::Isometry3d & getTransformFromParentBodyNode() const
Get transformation from parent body node to this joint.
Definition Joint.cpp:492
virtual void setPartialAccelerationTo(Eigen::Vector6d &_partialAcceleration, const Eigen::Vector6d &_childVelocity)=0
Set joint partial acceleration to _partialAcceleration.
virtual double getPositionLowerLimit(std::size_t _index) const =0
Get lower limit for position.
virtual void updateRelativeTransform() const =0
Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNod...
virtual double getPosition(std::size_t _index) const =0
Get the position of a single generalized coordinate.
virtual Eigen::VectorXd getPositions() const =0
Get the positions of all generalized coordinates in this Joint.
virtual void addChildBiasForceTo(Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce, const Eigen::Vector6d &_childPartialAcc)=0
Add child's bias force to parent's one.
virtual DegreeOfFreedom * getDof(std::size_t _index)=0
Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
void setPositionLimitEnforced(bool _isPositionLimitEnforced)
Set to enforce joint position limit.
Definition Joint.cpp:389
virtual double getCoulombFriction(std::size_t _index) const =0
Get joint Coulomb friction froce.
virtual void addChildArtInertiaTo(Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia)=0
Add child's articulated inertia to parent's one.
bool mIsRelativeJacobianTimeDerivDirty
True iff this joint's relative Jacobian time derivative has not been updated since the last position ...
Definition Joint.hpp:1013
virtual void addChildBiasForceForInvAugMassMatrix(Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
Add child's bias force to parent's one.
double getMimicOffset() const
Get mimic joint offset.
Definition Joint.cpp:226
Eigen::Isometry3d mT
Relative transformation of the child BodyNode relative to the parent BodyNode expressed in the child ...
Definition Joint.hpp:968
void updateLocalJacobianTimeDeriv() const
Deprecated. Use updateRelativeJacobianTimeDeriv() instead.
Definition Joint.cpp:557
const Eigen::Vector6d & getRelativeSpatialVelocity() const
Get spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child Bod...
Definition Joint.cpp:353
virtual void setCoulombFriction(std::size_t _index, double _friction)=0
Set joint Coulomb friction froce.
virtual void setCommands(const Eigen::VectorXd &_commands)=0
Set all commands for this Joint.
const math::Jacobian getLocalJacobianTimeDeriv() const
Deprecated. Use getRelativeJacobianTimeDeriv() instead.
Definition Joint.cpp:335
virtual const math::Jacobian getRelativeJacobian() const =0
Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child Bod...
virtual void setVelocityUpperLimit(std::size_t _index, double _velocity)=0
Set upper limit for velocity.
static constexpr ActuatorType MIMIC
Definition Joint.hpp:69
double getPotentialEnergy() const
Get potential energy.
Definition Joint.cpp:469
const Eigen::Isometry3d & getTransformFromChildBodyNode() const
Get transformation from child body node to this joint.
Definition Joint.cpp:498
double getMimicMultiplier() const
Get mimic joint multiplier.
Definition Joint.cpp:220
virtual void updateTotalForce(const Eigen::Vector6d &_bodyForce, double _timeStep)=0
Update joint total force.
virtual double getPositionUpperLimit(std::size_t _index) const =0
Get upper limit for position.
BodyNode * getChildBodyNode()
Get the child BodyNode of this Joint.
Definition Joint.cpp:260
virtual void setInitialPositions(const Eigen::VectorXd &_initial)=0
Change the positions that resetPositions() will give to this Joint's coordinates.
bool mIsRelativeJacobianDirty
True iff this joint's relative Jacobian has not been updated since the last position change.
Definition Joint.hpp:1009
void setMimicJoint(const Joint *_mimicJoint, double _mimicMultiplier=1.0, double _mimicOffset=0.0)
Set mimic joint.
Definition Joint.cpp:206
void updateLocalJacobian(bool mandatory=true) const
Deprecated. Use updateRelativeJacobian() instead.
Definition Joint.cpp:551
virtual Eigen::VectorXd getAccelerationUpperLimits() const =0
Get the acceleration upper limits of all the generalized coordinates.
virtual Eigen::VectorXd getPositionLowerLimits() const =0
Get the position lower limits of all the generalized coordinates.
virtual void updateAcceleration(const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
Update joint acceleration.
virtual void resetTotalImpulses()=0
Set total impulses to zero.
virtual void updateImpulseID(const Eigen::Vector6d &_bodyImpulse)=0
Update joint impulses for inverse dynamics.
virtual void setVelocityLowerLimit(std::size_t _index, double _velocity)=0
Set lower limit for velocity.
virtual void setPosition(std::size_t _index, double _position)=0
Set the position of a single generalized coordinate.
void setProperties(const Properties &properties)
Set the Properties of this Joint.
Definition Joint.cpp:110
bool isDynamic() const
Return true if this joint is dynamic joint.
Definition Joint.cpp:254
virtual bool isDofNamePreserved(std::size_t _index) const =0
Alternative to DegreeOfFreedom::isNamePreserved()
virtual void addVelocityTo(Eigen::Vector6d &_vel)=0
Add joint velocity to _vel.
virtual Eigen::VectorXd getVelocities() const =0
Get the velocities of all generalized coordinates in this Joint.
common::Composite::Properties CompositeProperties
Definition Joint.hpp:62
virtual void integrateVelocities(double _dt)=0
Integrate velocities using Euler method.
static constexpr ActuatorType VELOCITY
Definition Joint.hpp:71
const Eigen::Vector6d & getLocalPrimaryAcceleration() const
Deprecated. Use getLocalPrimaryAcceleration() instead.
Definition Joint.cpp:317
std::size_t getJointIndexInTree() const
Get the index of this Joint within its tree.
Definition Joint.cpp:407
virtual void updateRelativeSpatialAcceleration() const =0
Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the ch...
virtual ~Joint()
Destructor.
Definition Joint.cpp:104
virtual void setAccelerationUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the acceleration upper limits of all the generalized coordinates.
const math::Jacobian getLocalJacobian() const
Deprecated. Use getRelativeJacobian() instead.
Definition Joint.cpp:323
virtual std::size_t getIndexInSkeleton(std::size_t _index) const =0
Get a unique index in skeleton of a generalized coordinate in this Joint.
virtual bool isCyclic(std::size_t _index) const =0
Get whether a generalized coordinate is cyclic.
virtual Eigen::Vector6d getBodyConstraintWrench() const =0
Get constraint wrench expressed in body node frame.
virtual void setAccelerationUpperLimit(std::size_t _index, double _acceleration)=0
Set upper limit for acceleration.
class Skeleton
Definition Skeleton.hpp:59
SoftBodyNode represent a soft body that has one deformable skin.
Definition SoftBodyNode.hpp:46
#define DART_BAKE_SPECIALIZED_ASPECT_IRREGULAR(TypeName, AspectName)
Definition Composite.hpp:164
Definition Random-impl.hpp:92
ActuatorType
Actuator type.
Definition JointAspect.hpp:59
@ PASSIVE
Passive joint doesn't take any command input, and the output is joint acceleration.
Definition JointAspect.hpp:72
@ MIMIC
There is no command input.
Definition JointAspect.hpp:86
@ FORCE
Command input is joint force, and the output is joint acceleration.
Definition JointAspect.hpp:65
@ VELOCITY
Command input is joint velocity, and the output is joint force.
Definition JointAspect.hpp:99
@ ACCELERATION
Command input is joint acceleration, and the output is joint force.
Definition JointAspect.hpp:92
@ SERVO
Command input is desired velocity, and the output is joint acceleration.
Definition JointAspect.hpp:78
@ LOCKED
Locked joint always set the velocity and acceleration to zero so that the joint dosen't move at all (...
Definition JointAspect.hpp:106
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
Definition BulletCollisionDetector.cpp:63
Definition SharedLibraryManager.hpp:43
CompositeProperties mCompositeProperties
Properties of all the Aspects attached to this Joint.
Definition Joint.hpp:89
Definition JointAspect.hpp:112