All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::physics::Joint Class Referenceabstract

Base class for all joints. More...

#include <physics/physics.hh>

Inheritance diagram for gazebo::physics::Joint:
Inheritance graph
[legend]
Collaboration diagram for gazebo::physics::Joint:
Collaboration graph
[legend]

Public Types

enum  Attribute {
  FUDGE_FACTOR, SUSPENSION_ERP, SUSPENSION_CFM, STOP_ERP,
  STOP_CFM, ERP, CFM, FMAX,
  VEL, HI_STOP, LO_STOP
}
 Joint attribute types. More...
 
- Public Types inherited from gazebo::physics::Base
enum  EntityType {
  BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004,
  COLLISION = 0x00000008, ACTOR = 0x00000016, LIGHT = 0x00000010, VISUAL = 0x00000020,
  JOINT = 0x00000040, BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200,
  SLIDER_JOINT = 0x00000400, SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, GEARBOX_JOINT = 0x00002000,
  SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000, HEIGHTMAP_SHAPE = 0x00080000,
  MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000, PLANE_SHAPE = 0x00800000,
  SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000, SENSOR_COLLISION = 0x10000000
}
 Unique identifiers for all entity types. More...
 

Public Member Functions

 Joint (BasePtr _parent)
 Constructor. More...
 
virtual ~Joint ()
 Destructor. More...
 
virtual void ApplyStiffnessDamping ()
 Callback to apply spring stiffness and viscous damping effects to joint. More...
 
virtual bool AreConnected (LinkPtr _one, LinkPtr _two) const =0
 Determines of the two bodies are connected by a joint. More...
 
virtual void Attach (LinkPtr _parent, LinkPtr _child)
 Attach the two bodies with this joint. More...
 
virtual void CacheForceTorque ()
 Cache Joint Force Torque Values if necessary for physics engine. More...
 
double CheckAndTruncateForce (unsigned int _index, double _effort)
 check if the force against velocityLimit and effortLimit, truncate if necessary. More...
 
template<typename T >
event::ConnectionPtr ConnectJointUpdate (T _subscriber)
 Connect a boost::slot the the joint update signal. More...
 
virtual void Detach ()
 Detach this joint from all links. More...
 
void DisconnectJointUpdate (event::ConnectionPtr &_conn)
 Disconnect a boost::slot the the joint update signal. More...
 
void FillMsg (msgs::Joint &_msg)
 Fill a joint message. More...
 
virtual void Fini ()
 Finialize the object. More...
 
virtual math::Vector3 GetAnchor (unsigned int _index) const =0
 Get the anchor point. More...
 
math::Pose GetAnchorErrorPose () const
 Get pose offset between anchor pose on child and parent, expressed in the parent link frame. More...
 
math::Angle GetAngle (unsigned int _index) const
 Get the angle of rotation of an axis(index) More...
 
virtual unsigned int GetAngleCount () const =0
 Get the angle count. More...
 
math::Quaternion GetAxisFrame (unsigned int _index) const
 Get orientation of reference frame for specified axis, relative to world frame. More...
 
math::Quaternion GetAxisFrameOffset (unsigned int _index) const
 Get orientation of joint axis reference frame relative to joint frame. More...
 
LinkPtr GetChild () const
 Get the child link. More...
 
double GetDamping (unsigned int _index)
 Returns the current joint damping coefficient. More...
 
virtual double GetEffortLimit (unsigned int _index)
 Get the effort limit on axis(index). More...
 
virtual double GetForce (unsigned int _index)
 
virtual JointWrench GetForceTorque (unsigned int _index)=0
 get internal force and torque values at a joint. More...
 
virtual math::Vector3 GetGlobalAxis (unsigned int _index) const =0
 Get the axis of rotation in global cooridnate frame. More...
 
virtual math::Angle GetHighStop (unsigned int _index)=0
 Get the high stop of an axis(index). More...
 
double GetInertiaRatio (const unsigned int _index) const
 Computes moment of inertia (MOI) across a specified joint axis. More...
 
double GetInertiaRatio (const math::Vector3 &_axis) const
 Computes moment of inertia (MOI) across an arbitrary axis specified in the world frame. More...
 
math::Pose GetInitialAnchorPose () const
 Get initial Anchor Pose specified by model <joint><pose>...</pose></joint> More...
 
virtual LinkPtr GetJointLink (unsigned int _index) const =0
 Get the link to which the joint is attached according the _index. More...
 
virtual math::Vector3 GetLinkForce (unsigned int _index) const =0
 Get the forces applied to the center of mass of a physics::Link due to the existence of this Joint. More...
 
virtual math::Vector3 GetLinkTorque (unsigned int _index) const =0
 Get the torque applied to the center of mass of a physics::Link due to the existence of this Joint. More...
 
math::Vector3 GetLocalAxis (unsigned int _index) const
 Get the axis of rotation. More...
 
math::Angle GetLowerLimit (unsigned int _index) const
 : get the joint upper limit (replaces GetLowStop and GetHighStop) More...
 
virtual math::Angle GetLowStop (unsigned int _index)=0
 Get the low stop of an axis(index). More...
 
virtual double GetMaxForce (unsigned int _index)=0
 Get the max allowed force of an axis(index) when using Joint::SetVelocity. More...
 
virtual double GetParam (const std::string &_key, unsigned int _index)=0
 Get a non-generic parameter for the joint. More...
 
LinkPtr GetParent () const
 Get the parent link. More...
 
math::Pose GetParentWorldPose () const
 Get anchor pose on parent link relative to world frame. More...
 
double GetSpringReferencePosition (unsigned int _index) const
 Get joint spring reference position. More...
 
double GetStiffness (unsigned int _index)
 Returns the current joint spring stiffness coefficient. More...
 
double GetStopDissipation (unsigned int _index) const
 Get joint stop dissipation. More...
 
double GetStopStiffness (unsigned int _index) const
 Get joint stop stiffness. More...
 
math::Angle GetUpperLimit (unsigned int _index) const
 : get the joint lower limit (replacee GetLowStop and GetHighStop) More...
 
virtual double GetVelocity (unsigned int _index) const =0
 Get the rotation rate of an axis(index) More...
 
virtual double GetVelocityLimit (unsigned int _index)
 Get the velocity limit on axis(index). More...
 
double GetWorldEnergyPotentialSpring (unsigned int _index) const
 Returns this joint's spring potential energy, based on the reference position of the spring. More...
 
math::Pose GetWorldPose () const
 Get pose of joint frame relative to world frame. More...
 
virtual void Init ()
 Initialize a joint. More...
 
void Load (LinkPtr _parent, LinkPtr _child, const math::Pose &_pose)
 Set pose, parent and child links of a physics::Joint. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load physics::Joint from a SDF sdf::Element. More...
 
virtual void Reset ()
 Reset the joint. More...
 
virtual void SetAnchor (unsigned int _index, const math::Vector3 &_anchor)=0
 Set the anchor point. More...
 
void SetAngle (unsigned int _index, math::Angle _angle) GAZEBO_DEPRECATED(4.0)
 If the Joint is static, Gazebo stores the state of this Joint as a scalar inside the Joint class, so this call will NOT move the joint dynamically for a static Model. More...
 
virtual void SetAxis (unsigned int _index, const math::Vector3 &_axis)=0
 Set the axis of rotation where axis is specified in local joint frame. More...
 
virtual void SetDamping (unsigned int _index, double _damping)=0
 Set the joint damping. More...
 
virtual void SetEffortLimit (unsigned int _index, double _effort)
 Set the effort limit on a joint axis. More...
 
virtual void SetForce (unsigned int _index, double _effort)=0
 Set the force applied to this physics::Joint. More...
 
virtual bool SetHighStop (unsigned int _index, const math::Angle &_angle)
 Set the high stop of an axis(index). More...
 
void SetLowerLimit (unsigned int _index, math::Angle _limit)
 : set the joint upper limit (replaces SetLowStop and SetHighStop) More...
 
virtual bool SetLowStop (unsigned int _index, const math::Angle &_angle)
 Set the low stop of an axis(index). More...
 
virtual void SetMaxForce (unsigned int _index, double _force)=0
 Set the max allowed force of an axis(index) when using Joint::SetVelocity. More...
 
void SetModel (ModelPtr _model)
 Set the model this joint belongs too. More...
 
virtual bool SetParam (const std::string &_key, unsigned int _index, const boost::any &_value)=0
 Set a non-generic parameter for the joint. More...
 
virtual bool SetPosition (unsigned int _index, double _position)
 The child links of this joint are updated based on desired position. More...
 
virtual void SetProvideFeedback (bool _enable)
 Set whether the joint should generate feedback. More...
 
void SetState (const JointState &_state)
 Set the joint state. More...
 
virtual void SetStiffness (unsigned int _index, double _stiffness)=0
 Set the joint spring stiffness. More...
 
virtual void SetStiffnessDamping (unsigned int _index, double _stiffness, double _damping, double _reference=0)=0
 Set the joint spring stiffness. More...
 
void SetStopDissipation (unsigned int _index, double _dissipation)
 Set joint stop dissipation. More...
 
void SetStopStiffness (unsigned int _index, double _stiffness)
 Set joint stop stiffness. More...
 
void SetUpperLimit (unsigned int _index, math::Angle _limit)
 : set the joint lower limit (replacee GetLowStop and GetHighStop) More...
 
virtual void SetVelocity (unsigned int _index, double _vel)=0
 Set the velocity of an axis(index). More...
 
void Update ()
 Update the joint. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 Update the parameters using new sdf values. More...
 
- Public Member Functions inherited from gazebo::physics::Base
 Base (BasePtr _parent)
 Constructor. More...
 
virtual ~Base ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
BasePtr GetByName (const std::string &_name)
 Get by name. More...
 
BasePtr GetChild (unsigned int _i) const
 Get a child by index. More...
 
BasePtr GetChild (const std::string &_name)
 Get a child by name. More...
 
unsigned int GetChildCount () const
 Get the number of children. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
std::string GetName () const
 Return the name of the entity. More...
 
BasePtr GetParent () const
 Get the parent. More...
 
int GetParentId () const
 Return the ID of the parent. More...
 
bool GetSaveable () const
 Get whether the object should be "saved", when the user selects to save the world to xml. More...
 
std::string GetScopedName (bool _prependWorldName=false) const
 Return the name of this entity with the model scope model1::...::modelN::entityName. More...
 
virtual const sdf::ElementPtr GetSDF ()
 Get the SDF values for the object. More...
 
unsigned int GetType () const
 Get the full type definition. More...
 
const WorldPtrGetWorld () const
 Get the World this object is in. More...
 
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type. More...
 
bool IsSelected () const
 True if the entity is selected by the user. More...
 
bool operator== (const Base &_ent) const
 Returns true if the entities are the same. More...
 
void Print (const std::string &_prefix)
 Print this object to screen via gzmsg. More...
 
virtual void RemoveChild (unsigned int _id)
 Remove a child from this entity. More...
 
void RemoveChild (const std::string &_name)
 Remove a child by name. More...
 
void RemoveChildren ()
 Remove all children. More...
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's. More...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
void SetSaveable (bool _v)
 Set whether the object should be "saved", when the user selects to save the world to xml. More...
 
virtual bool SetSelected (bool _show)
 Set whether this entity has been selected by the user through the gui. More...
 
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to. More...
 

Protected Member Functions

math::Pose ComputeChildLinkPose (unsigned int _index, double _position)
 internal function to help us compute child link pose if a joint position change is applied. More...
 
bool FindAllConnectedLinks (const LinkPtr &_originalParentLink, Link_V &_connectedLinks)
 internal helper to find all links connected to the child link branching out from the children of the child link and any parent of the child link other than the parent link through this joint. More...
 
virtual math::Angle GetAngleImpl (unsigned int _index) const =0
 Get the angle of an axis helper function. More...
 
bool SetPositionMaximal (unsigned int _index, double _position)
 Helper function for maximal coordinate solver SetPosition. More...
 
- Protected Member Functions inherited from gazebo::physics::Base
void ComputeScopedName ()
 Compute the scoped name of this object based on its parents. More...
 

Protected Attributes

LinkPtr anchorLink
 Anchor link. More...
 
math::Vector3 anchorPos
 Anchor pose. More...
 
math::Pose anchorPose
 Anchor pose specified in SDF <joint><pose> tag. More...
 
gazebo::event::ConnectionPtr applyDamping
 apply damping for adding viscous damping forces on updates More...
 
bool axisParentModelFrame [2]
 Flags that are set to true if an axis value is expressed in the parent model frame. More...
 
LinkPtr childLink
 The first link this joint connects to. More...
 
double dissipationCoefficient [2]
 joint viscous damping coefficient More...
 
double effortLimit [2]
 Store Joint effort limit as specified in SDF. More...
 
math::Angle lowerLimit [2]
 Store Joint position lower limit as specified in SDF. More...
 
ModelPtr model
 Pointer to the parent model. More...
 
math::Pose parentAnchorPose
 Anchor pose relative to parent link frame. More...
 
LinkPtr parentLink
 The second link this joint connects to. More...
 
bool provideFeedback
 Provide Feedback data for contact forces. More...
 
double springReferencePosition [2]
 joint spring reference (zero load) position More...
 
double stiffnessCoefficient [2]
 joint stiffnessCoefficient More...
 
math::Angle upperLimit [2]
 Store Joint position upper limit as specified in SDF. More...
 
double velocityLimit [2]
 Store Joint velocity limit as specified in SDF. More...
 
JointWrench wrench
 Cache Joint force torque values in case physics engine clears them at the end of update step. More...
 
- Protected Attributes inherited from gazebo::physics::Base
Base_V children
 Children of this entity. More...
 
BasePtr parent
 Parent of this entity. More...
 
sdf::ElementPtr sdf
 The SDF values for this object. More...
 
WorldPtr world
 Pointer to the world. More...
 

Detailed Description

Base class for all joints.

Member Enumeration Documentation

Joint attribute types.

Enumerator
FUDGE_FACTOR 

Fudge factor.

SUSPENSION_ERP 

Suspension error reduction parameter.

SUSPENSION_CFM 

Suspension constraint force mixing.

STOP_ERP 

Stop limit error reduction parameter.

STOP_CFM 

Stop limit constraint force mixing.

ERP 

Error reduction parameter.

CFM 

Constraint force mixing.

FMAX 

Maximum force.

VEL 

Velocity.

HI_STOP 

High stop angle.

LO_STOP 

Low stop angle.

Constructor & Destructor Documentation

gazebo::physics::Joint::Joint ( BasePtr  _parent)
explicit

Constructor.

Parameters
[in]Jointparent
virtual gazebo::physics::Joint::~Joint ( )
virtual

Destructor.

Member Function Documentation

virtual void gazebo::physics::Joint::ApplyStiffnessDamping ( )
virtual

Callback to apply spring stiffness and viscous damping effects to joint.

: rename to ApplySpringStiffnessDamping()

Reimplemented in gazebo::physics::ODEJoint, and gazebo::physics::BulletJoint.

virtual bool gazebo::physics::Joint::AreConnected ( LinkPtr  _one,
LinkPtr  _two 
) const
pure virtual

Determines of the two bodies are connected by a joint.

Parameters
[in]_oneFirst link.
[in]_twoSecond link.
Returns
True if the two links are connected by a joint.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, and gazebo::physics::SimbodyJoint.

virtual void gazebo::physics::Joint::Attach ( LinkPtr  _parent,
LinkPtr  _child 
)
virtual

Attach the two bodies with this joint.

Parameters
[in]_parentParent link.
[in]_childChild link.

Reimplemented in gazebo::physics::ODEJoint, and gazebo::physics::DARTJoint.

virtual void gazebo::physics::Joint::CacheForceTorque ( )
virtual

Cache Joint Force Torque Values if necessary for physics engine.

Reimplemented in gazebo::physics::SimbodyJoint, and gazebo::physics::BulletJoint.

double gazebo::physics::Joint::CheckAndTruncateForce ( unsigned int  _index,
double  _effort 
)

check if the force against velocityLimit and effortLimit, truncate if necessary.

Parameters
[in]_indexIndex of the axis.
[in]_effortForce value.
Returns
truncated effort
math::Pose gazebo::physics::Joint::ComputeChildLinkPose ( unsigned int  _index,
double  _position 
)
protected

internal function to help us compute child link pose if a joint position change is applied.

Parameters
[in]_indexaxis index
[in]_positionnew joint position
Returns
new child link pose at new joint position.
template<typename T >
event::ConnectionPtr gazebo::physics::Joint::ConnectJointUpdate ( _subscriber)
inline

Connect a boost::slot the the joint update signal.

Parameters
[in]_subscriberCallback for the connection.
Returns
Connection pointer, which must be kept in scope.
virtual void gazebo::physics::Joint::Detach ( )
virtual
void gazebo::physics::Joint::DisconnectJointUpdate ( event::ConnectionPtr _conn)
inline

Disconnect a boost::slot the the joint update signal.

Parameters
[in]_connConnection to disconnect.
void gazebo::physics::Joint::FillMsg ( msgs::Joint &  _msg)

Fill a joint message.

Parameters
[out]_msgMessage to fill with this joint's properties.
bool gazebo::physics::Joint::FindAllConnectedLinks ( const LinkPtr _originalParentLink,
Link_V _connectedLinks 
)
protected

internal helper to find all links connected to the child link branching out from the children of the child link and any parent of the child link other than the parent link through this joint.

Parameters
[in]_originalParentLinkparent link of this joint, this is used to check for loops connecting back to the parent link.
in/out]_connectedLinks list of aggregated links that contains all links connected to the child link of this joint. Empty if a loop is found that connects back to the parent link.
Returns
true if successful, false if a loop is found that connects back to the parent link.
virtual void gazebo::physics::Joint::Fini ( )
virtual

Finialize the object.

Reimplemented from gazebo::physics::Base.

virtual math::Vector3 gazebo::physics::Joint::GetAnchor ( unsigned int  _index) const
pure virtual
math::Pose gazebo::physics::Joint::GetAnchorErrorPose ( ) const

Get pose offset between anchor pose on child and parent, expressed in the parent link frame.

This can be used to compute the bilateral constraint error.

Returns
Pose offset between anchor pose on child and parent, in parent link frame.
math::Angle gazebo::physics::Joint::GetAngle ( unsigned int  _index) const

Get the angle of rotation of an axis(index)

Parameters
[in]_indexIndex of the axis.
Returns
Angle of the axis.
virtual unsigned int gazebo::physics::Joint::GetAngleCount ( ) const
pure virtual
virtual math::Angle gazebo::physics::Joint::GetAngleImpl ( unsigned int  _index) const
protectedpure virtual
math::Quaternion gazebo::physics::Joint::GetAxisFrame ( unsigned int  _index) const

Get orientation of reference frame for specified axis, relative to world frame.

The value of axisParentModelFrame is used to determine the appropriate frame.

Parameters
[in]_indexjoint axis index.
Returns
Orientation of axis frame relative to world frame.
math::Quaternion gazebo::physics::Joint::GetAxisFrameOffset ( unsigned int  _index) const

Get orientation of joint axis reference frame relative to joint frame.

This should always return identity unless flag use_parent_model_frame is true in sdf 1.5 or using sdf 1.4-, i.e. bug described in issue #494 is present. In addition, if use_parent_model_frame is true, and the parent link of the joint is world, the axis is defined in the world frame. The value of axisParentModelFrame is used to determine the appropriate frame internally.

Parameters
[in]_indexjoint axis index.
Returns
Orientation of axis frame relative to joint frame. If supplied _index is out of range, or use_parent_model_frame is not true, this function returns identity rotation quaternion.
LinkPtr gazebo::physics::Joint::GetChild ( ) const

Get the child link.

Returns
Pointer to the child link.
double gazebo::physics::Joint::GetDamping ( unsigned int  _index)

Returns the current joint damping coefficient.

Parameters
[in]_indexIndex of the axis to get, currently ignored, to be implemented.
Returns
Joint viscous damping coefficient for this joint.
virtual double gazebo::physics::Joint::GetEffortLimit ( unsigned int  _index)
virtual

Get the effort limit on axis(index).

Parameters
[in]_indexIndex of axis, where 0=first axis and 1=second axis
Returns
Effort limit specified in SDF
virtual double gazebo::physics::Joint::GetForce ( unsigned int  _index)
virtual
Todo:
: not yet implemented. Get external forces applied at this Joint. Note that the unit of force should be consistent with the rest of the simulation scales.
Parameters
[in]_indexIndex of the axis.
Returns
The force applied to an axis.

Reimplemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, and gazebo::physics::SimbodyJoint.

virtual JointWrench gazebo::physics::Joint::GetForceTorque ( unsigned int  _index)
pure virtual

get internal force and torque values at a joint.

The force and torque values are returned in a JointWrench data structure. Where JointWrench.body1Force contains the force applied by the parent Link on the Joint specified in the parent Link frame, and JointWrench.body2Force contains the force applied by the child Link on the Joint specified in the child Link frame. Note that this sign convention is opposite of the reaction forces of the Joint on the Links.

FIXME TODO: change name of this function to something like: GetNegatedForceTorqueInLinkFrame and make GetForceTorque call return non-negated reaction forces in perspective Link frames.

Note that for ODE you must set <provide_feedback>true<provide_feedback> in the joint sdf to use this.

Parameters
[in]_indexNot used right now
Returns
The force and torque at the joint, see above for details on conventions.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::SimbodyJoint, and gazebo::physics::DARTJoint.

virtual math::Vector3 gazebo::physics::Joint::GetGlobalAxis ( unsigned int  _index) const
pure virtual
virtual math::Angle gazebo::physics::Joint::GetHighStop ( unsigned int  _index)
pure virtual

Get the high stop of an axis(index).

This function is replaced by GetUpperLimit(unsigned int). If you are interested in getting the value of dParamHiStop*, use GetAttribute(hi_stop, _index)

Parameters
[in]_indexIndex of the axis.
Returns
Angle of the high stop value.

Implemented in gazebo::physics::SimbodyJoint, gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::BulletBallJoint, gazebo::physics::DARTScrewJoint, gazebo::physics::BulletHinge2Joint, gazebo::physics::DARTJoint, gazebo::physics::BulletHingeJoint, gazebo::physics::BulletUniversalJoint, gazebo::physics::SimbodyBallJoint, gazebo::physics::DARTBallJoint, gazebo::physics::ODEBallJoint, gazebo::physics::BulletSliderJoint, and gazebo::physics::SimbodyScrewJoint.

double gazebo::physics::Joint::GetInertiaRatio ( const unsigned int  _index) const

Computes moment of inertia (MOI) across a specified joint axis.

The ratio is given in the form of MOI_chidl / MOI_parent. If MOI_parent is zero, this funciton will return 0. The inertia ratio for each joint axis indicates the sensitivity of the joint to actuation torques.

Parameters
[in]_indexaxis number about which MOI ratio is computed.
Returns
ratio of child MOI to parent MOI.
double gazebo::physics::Joint::GetInertiaRatio ( const math::Vector3 _axis) const

Computes moment of inertia (MOI) across an arbitrary axis specified in the world frame.

The ratio is given in the form of MOI_chidl / MOI_parent. If MOI_parent is zero, this funciton will return 0. The moment of inertia ratio along constrained directions of a joint has an impact on the performance of Projected Gauss Seidel (PGS) iterative LCP methods.

Parameters
[in]_axisaxis in world frame for which MOI ratio is computed.
Returns
ratio of child MOI to parent MOI.
math::Pose gazebo::physics::Joint::GetInitialAnchorPose ( ) const

Get initial Anchor Pose specified by model <joint><pose>...</pose></joint>

Returns
Joint::anchorPose, initial joint anchor pose.
virtual LinkPtr gazebo::physics::Joint::GetJointLink ( unsigned int  _index) const
pure virtual

Get the link to which the joint is attached according the _index.

Parameters
[in]_indexIndex of the link to retreive.
Returns
Pointer to the request link. NULL if the index was invalid.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, and gazebo::physics::SimbodyJoint.

virtual math::Vector3 gazebo::physics::Joint::GetLinkForce ( unsigned int  _index) const
pure virtual

Get the forces applied to the center of mass of a physics::Link due to the existence of this Joint.

Note that the unit of force should be consistent with the rest of the simulation scales.

Parameters
[in]indexThe index of the link(0 or 1).
Returns
Force applied to the link.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::DARTJoint, gazebo::physics::BulletJoint, and gazebo::physics::SimbodyJoint.

virtual math::Vector3 gazebo::physics::Joint::GetLinkTorque ( unsigned int  _index) const
pure virtual

Get the torque applied to the center of mass of a physics::Link due to the existence of this Joint.

Note that the unit of torque should be consistent with the rest of the simulation scales.

Parameters
[in]indexThe index of the link(0 or 1)
Returns
Torque applied to the link.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::DARTJoint, gazebo::physics::BulletJoint, and gazebo::physics::SimbodyJoint.

math::Vector3 gazebo::physics::Joint::GetLocalAxis ( unsigned int  _index) const

Get the axis of rotation.

Parameters
[in]_indexIndex of the axis to get.
Returns
Axis value for the provided index.
math::Angle gazebo::physics::Joint::GetLowerLimit ( unsigned int  _index) const

: get the joint upper limit (replaces GetLowStop and GetHighStop)

Parameters
[in]_indexIndex of the axis.
Returns
Lower limit of the axis.
virtual math::Angle gazebo::physics::Joint::GetLowStop ( unsigned int  _index)
pure virtual

Get the low stop of an axis(index).

This function is replaced by GetLowerLimit(unsigned int). If you are interested in getting the value of dParamHiStop*, use GetAttribute(hi_stop, _index)

Parameters
[in]_indexIndex of the axis.
Returns
Angle of the low stop value.

Implemented in gazebo::physics::SimbodyJoint, gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::BulletBallJoint, gazebo::physics::DARTScrewJoint, gazebo::physics::BulletHinge2Joint, gazebo::physics::DARTJoint, gazebo::physics::BulletHingeJoint, gazebo::physics::BulletUniversalJoint, gazebo::physics::SimbodyBallJoint, gazebo::physics::DARTBallJoint, gazebo::physics::ODEBallJoint, gazebo::physics::BulletSliderJoint, and gazebo::physics::SimbodyScrewJoint.

virtual double gazebo::physics::Joint::GetMaxForce ( unsigned int  _index)
pure virtual
virtual double gazebo::physics::Joint::GetParam ( const std::string &  _key,
unsigned int  _index 
)
pure virtual
LinkPtr gazebo::physics::Joint::GetParent ( ) const

Get the parent link.

Returns
Pointer to the parent link.
math::Pose gazebo::physics::Joint::GetParentWorldPose ( ) const

Get anchor pose on parent link relative to world frame.

When there is zero joint error, this should match the value returned by Joint::GetWorldPose() for the constrained degrees of freedom.

Returns
Anchor pose on parent link in world frame.
double gazebo::physics::Joint::GetSpringReferencePosition ( unsigned int  _index) const

Get joint spring reference position.

Parameters
[in]_indexIndex of the axis to get.
Returns
Joint spring reference position (in radians for angular joints).
double gazebo::physics::Joint::GetStiffness ( unsigned int  _index)

Returns the current joint spring stiffness coefficient.

Parameters
[in]_indexIndex of the axis to get, currently ignored, to be implemented.
Returns
Joint spring stiffness coefficient for this joint. : rename to GetSpringStiffness()
double gazebo::physics::Joint::GetStopDissipation ( unsigned int  _index) const

Get joint stop dissipation.

Parameters
[in]_indexjoint axis index.
Returns
joint stop dissipation coefficient.
double gazebo::physics::Joint::GetStopStiffness ( unsigned int  _index) const

Get joint stop stiffness.

Parameters
[in]_indexjoint axis index.
Returns
joint stop stiffness coefficient.
math::Angle gazebo::physics::Joint::GetUpperLimit ( unsigned int  _index) const

: get the joint lower limit (replacee GetLowStop and GetHighStop)

Parameters
[in]_indexIndex of the axis.
Returns
Upper limit of the axis.
virtual double gazebo::physics::Joint::GetVelocity ( unsigned int  _index) const
pure virtual
virtual double gazebo::physics::Joint::GetVelocityLimit ( unsigned int  _index)
virtual

Get the velocity limit on axis(index).

Parameters
[in]_indexIndex of axis, where 0=first axis and 1=second axis
Returns
Velocity limit specified in SDF
double gazebo::physics::Joint::GetWorldEnergyPotentialSpring ( unsigned int  _index) const

Returns this joint's spring potential energy, based on the reference position of the spring.

If using metric system, the unit of energy will be Joules.

Returns
this joint's spring potential energy,
math::Pose gazebo::physics::Joint::GetWorldPose ( ) const

Get pose of joint frame relative to world frame.

Note that the joint frame is defined with a fixed offset from the child link frame.

Returns
Pose of joint frame relative to world frame.
virtual void gazebo::physics::Joint::Init ( )
virtual
void gazebo::physics::Joint::Load ( LinkPtr  _parent,
LinkPtr  _child,
const math::Pose _pose 
)

Set pose, parent and child links of a physics::Joint.

Parameters
[in]_parentParent link.
[in]_childChild link.
[in]_posePose containing Joint Anchor offset from child link.
virtual void gazebo::physics::Joint::Load ( sdf::ElementPtr  _sdf)
virtual

Load physics::Joint from a SDF sdf::Element.

Parameters
[in]_sdfSDF values to load from.

Reimplemented from gazebo::physics::Base.

Reimplemented in gazebo::physics::SimbodySliderJoint, gazebo::physics::BallJoint< ODEJoint >, gazebo::physics::BallJoint< DARTJoint >, gazebo::physics::BallJoint< SimbodyJoint >, gazebo::physics::BallJoint< BulletJoint >, gazebo::physics::UniversalJoint< ODEJoint >, gazebo::physics::UniversalJoint< DARTJoint >, gazebo::physics::UniversalJoint< SimbodyJoint >, gazebo::physics::UniversalJoint< BulletJoint >, gazebo::physics::Hinge2Joint< ODEJoint >, gazebo::physics::Hinge2Joint< DARTJoint >, gazebo::physics::Hinge2Joint< SimbodyJoint >, gazebo::physics::Hinge2Joint< BulletJoint >, gazebo::physics::HingeJoint< ODEJoint >, gazebo::physics::HingeJoint< DARTJoint >, gazebo::physics::HingeJoint< SimbodyJoint >, gazebo::physics::HingeJoint< BulletJoint >, gazebo::physics::BulletScrewJoint, gazebo::physics::ODEJoint, gazebo::physics::GearboxJoint< ODEJoint >, gazebo::physics::BulletHinge2Joint, gazebo::physics::ScrewJoint< ODEJoint >, gazebo::physics::ScrewJoint< DARTJoint >, gazebo::physics::ScrewJoint< SimbodyJoint >, gazebo::physics::ScrewJoint< BulletJoint >, gazebo::physics::SliderJoint< ODEJoint >, gazebo::physics::SliderJoint< DARTJoint >, gazebo::physics::SliderJoint< SimbodyJoint >, gazebo::physics::SliderJoint< BulletJoint >, gazebo::physics::BulletBallJoint, gazebo::physics::BulletJoint, gazebo::physics::ODEHinge2Joint, gazebo::physics::ODEHingeJoint, gazebo::physics::SimbodyHingeJoint, gazebo::physics::SimbodyUniversalJoint, gazebo::physics::BulletHingeJoint, gazebo::physics::BulletUniversalJoint, gazebo::physics::SimbodyHinge2Joint, gazebo::physics::SimbodyScrewJoint, gazebo::physics::BulletSliderJoint, gazebo::physics::SimbodyJoint, gazebo::physics::DARTJoint, gazebo::physics::ODEGearboxJoint, gazebo::physics::ODESliderJoint, gazebo::physics::SimbodyBallJoint, gazebo::physics::DARTHinge2Joint, gazebo::physics::DARTHingeJoint, gazebo::physics::DARTScrewJoint, gazebo::physics::ODEScrewJoint, gazebo::physics::DARTBallJoint, gazebo::physics::DARTSliderJoint, and gazebo::physics::DARTUniversalJoint.

virtual void gazebo::physics::Joint::Reset ( )
virtual
virtual void gazebo::physics::Joint::SetAnchor ( unsigned int  _index,
const math::Vector3 _anchor 
)
pure virtual
void gazebo::physics::Joint::SetAngle ( unsigned int  _index,
math::Angle  _angle 
)

If the Joint is static, Gazebo stores the state of this Joint as a scalar inside the Joint class, so this call will NOT move the joint dynamically for a static Model.

But if this Model is not static, then it is updated dynamically. The child links of this joint are updated based on position change. And all the links connected to the child link of this joint except through the parent link of this joint moves with the child link.

Parameters
[in]_indexIndex of the axis.
[in]_angleAngle to set the joint to.
virtual void gazebo::physics::Joint::SetAxis ( unsigned int  _index,
const math::Vector3 _axis 
)
pure virtual
virtual void gazebo::physics::Joint::SetDamping ( unsigned int  _index,
double  _damping 
)
pure virtual

Set the joint damping.

Parameters
[in]_indexIndex of the axis to set, currently ignored, to be implemented.
[in]_dampingDamping value for the axis.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, gazebo::physics::SimbodyJoint, and gazebo::physics::BulletSliderJoint.

virtual void gazebo::physics::Joint::SetEffortLimit ( unsigned int  _index,
double  _effort 
)
virtual

Set the effort limit on a joint axis.

Parameters
[in]_indexIndex of the axis to set.
[in]_effortEffort limit for the axis.
virtual void gazebo::physics::Joint::SetForce ( unsigned int  _index,
double  _effort 
)
pure virtual

Set the force applied to this physics::Joint.

Note that the unit of force should be consistent with the rest of the simulation scales. Force is additive (multiple calls to SetForce to the same joint in the same time step will accumulate forces on that Joint). Forces are truncated by effortLimit before applied.

Parameters
[in]_indexIndex of the axis.
[in]_effortForce value.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, and gazebo::physics::SimbodyJoint.

virtual bool gazebo::physics::Joint::SetHighStop ( unsigned int  _index,
const math::Angle _angle 
)
virtual
void gazebo::physics::Joint::SetLowerLimit ( unsigned int  _index,
math::Angle  _limit 
)

: set the joint upper limit (replaces SetLowStop and SetHighStop)

Parameters
[in]_indexIndex of the axis.
[in]_limitLower limit of the axis.
virtual bool gazebo::physics::Joint::SetLowStop ( unsigned int  _index,
const math::Angle _angle 
)
virtual
virtual void gazebo::physics::Joint::SetMaxForce ( unsigned int  _index,
double  _force 
)
pure virtual
void gazebo::physics::Joint::SetModel ( ModelPtr  _model)

Set the model this joint belongs too.

Parameters
[in]_modelPointer to a model.
virtual bool gazebo::physics::Joint::SetParam ( const std::string &  _key,
unsigned int  _index,
const boost::any &  _value 
)
pure virtual

Set a non-generic parameter for the joint.

replaces SetAttribute(Attribute, int, double)

Parameters
[in]_keyString key.
[in]_indexIndex of the axis.
[in]_valueValue of the attribute.

Implemented in gazebo::physics::ODEJoint, gazebo::physics::DARTJoint, gazebo::physics::BulletJoint, gazebo::physics::SimbodyScrewJoint, gazebo::physics::ODEScrewJoint, gazebo::physics::SimbodyJoint, and gazebo::physics::ODEUniversalJoint.

virtual bool gazebo::physics::Joint::SetPosition ( unsigned int  _index,
double  _position 
)
virtual

The child links of this joint are updated based on desired position.

And all the links connected to the child link of this joint except through the parent link of this joint moves with the child link.

Parameters
[in]_indexIndex of the joint axis (degree of freedom).
[in]_positionPosition to set the joint to. unspecified, pure kinematic teleportation.
Returns
returns true if operation succeeds, 0 if it fails.

Reimplemented in gazebo::physics::ODEJoint, and gazebo::physics::BulletJoint.

bool gazebo::physics::Joint::SetPositionMaximal ( unsigned int  _index,
double  _position 
)
protected

Helper function for maximal coordinate solver SetPosition.

The child links of this joint are updated based on position change. And all the links connected to the child link of this joint except through the parent link of this joint moves with the child link.

Parameters
[in]_indexIndex of the joint axis (degree of freedom).
[in]_positionPosition to set the joint to. unspecified, pure kinematic teleportation.
Returns
returns true if operation succeeds, 0 if it fails.
virtual void gazebo::physics::Joint::SetProvideFeedback ( bool  _enable)
virtual

Set whether the joint should generate feedback.

Parameters
[in]_enableTrue to enable joint feedback.

Reimplemented in gazebo::physics::ODEJoint.

void gazebo::physics::Joint::SetState ( const JointState _state)

Set the joint state.

Parameters
[in]_stateJoint state
virtual void gazebo::physics::Joint::SetStiffness ( unsigned int  _index,
double  _stiffness 
)
pure virtual

Set the joint spring stiffness.

Parameters
[in]_indexIndex of the axis to set, currently ignored, to be implemented.
[in]_stiffnessSpring stiffness value for the axis. : rename to SetSpringStiffness()

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, and gazebo::physics::SimbodyJoint.

virtual void gazebo::physics::Joint::SetStiffnessDamping ( unsigned int  _index,
double  _stiffness,
double  _damping,
double  _reference = 0 
)
pure virtual

Set the joint spring stiffness.

Parameters
[in]_indexIndex of the axis to set, currently ignored, to be implemented.
[in]_stiffnessStiffness value for the axis.
[in]_referenceSpring zero load reference position. : rename to SetSpringStiffnessDamping()

Implemented in gazebo::physics::ODEJoint, gazebo::physics::BulletJoint, gazebo::physics::DARTJoint, and gazebo::physics::SimbodyJoint.

void gazebo::physics::Joint::SetStopDissipation ( unsigned int  _index,
double  _dissipation 
)

Set joint stop dissipation.

Parameters
[in]_indexjoint axis index.
[in]_dissipationjoint stop dissipation coefficient.
void gazebo::physics::Joint::SetStopStiffness ( unsigned int  _index,
double  _stiffness 
)

Set joint stop stiffness.

Parameters
[in]_indexjoint axis index.
[in]_stiffnessjoint stop stiffness coefficient.
void gazebo::physics::Joint::SetUpperLimit ( unsigned int  _index,
math::Angle  _limit 
)

: set the joint lower limit (replacee GetLowStop and GetHighStop)

Parameters
[in]_indexIndex of the axis.
[in]_limitUpper limit of the axis.
virtual void gazebo::physics::Joint::SetVelocity ( unsigned int  _index,
double  _vel 
)
pure virtual
void gazebo::physics::Joint::Update ( )
virtual

Update the joint.

Reimplemented from gazebo::physics::Base.

virtual void gazebo::physics::Joint::UpdateParameters ( sdf::ElementPtr  _sdf)
virtual

Update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to update from.

Reimplemented from gazebo::physics::Base.

Member Data Documentation

LinkPtr gazebo::physics::Joint::anchorLink
protected

Anchor link.

math::Vector3 gazebo::physics::Joint::anchorPos
protected

Anchor pose.

This is the xyz offset of the joint frame from child frame specified in the parent link frame

math::Pose gazebo::physics::Joint::anchorPose
protected

Anchor pose specified in SDF <joint><pose> tag.

AnchorPose is the transform from child link frame to joint frame specified in the child link frame. AnchorPos is more relevant in normal usage, but sometimes, we do need this (e.g. GetForceTorque and joint visualization).

gazebo::event::ConnectionPtr gazebo::physics::Joint::applyDamping
protected

apply damping for adding viscous damping forces on updates

bool gazebo::physics::Joint::axisParentModelFrame[2]
protected

Flags that are set to true if an axis value is expressed in the parent model frame.

Otherwise use the joint frame. See issue #494.

LinkPtr gazebo::physics::Joint::childLink
protected

The first link this joint connects to.

double gazebo::physics::Joint::dissipationCoefficient[2]
protected

joint viscous damping coefficient

double gazebo::physics::Joint::effortLimit[2]
protected

Store Joint effort limit as specified in SDF.

math::Angle gazebo::physics::Joint::lowerLimit[2]
protected

Store Joint position lower limit as specified in SDF.

ModelPtr gazebo::physics::Joint::model
protected

Pointer to the parent model.

math::Pose gazebo::physics::Joint::parentAnchorPose
protected

Anchor pose relative to parent link frame.

LinkPtr gazebo::physics::Joint::parentLink
protected

The second link this joint connects to.

bool gazebo::physics::Joint::provideFeedback
protected

Provide Feedback data for contact forces.

double gazebo::physics::Joint::springReferencePosition[2]
protected

joint spring reference (zero load) position

double gazebo::physics::Joint::stiffnessCoefficient[2]
protected

joint stiffnessCoefficient

math::Angle gazebo::physics::Joint::upperLimit[2]
protected

Store Joint position upper limit as specified in SDF.

double gazebo::physics::Joint::velocityLimit[2]
protected

Store Joint velocity limit as specified in SDF.

JointWrench gazebo::physics::Joint::wrench
protected

Cache Joint force torque values in case physics engine clears them at the end of update step.


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