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

Base class for all joints. More...

#include <physics/physics.hh>

Inheritance diagram for gazebo::physics::Joint:
Inheritance 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, SHAPE = 0x00002000,
  BOX_SHAPE = 0x00004000, CYLINDER_SHAPE = 0x00008000, HEIGHTMAP_SHAPE = 0x00010000, MAP_SHAPE = 0x00020000,
  MULTIRAY_SHAPE = 0x00040000, RAY_SHAPE = 0x00080000, PLANE_SHAPE = 0x00100000, SPHERE_SHAPE = 0x00200000,
  MESH_SHAPE = 0x00400000, SENSOR_COLLISION = 0x00800000
}
 Unique identifiers for all entity types. More...

Public Member Functions

 Joint (BasePtr _parent)
 Constructor.
virtual ~Joint ()
 Destructor.
virtual void ApplyDamping ()
 Callback to apply damping force to joint.
virtual bool AreConnected (LinkPtr _one, LinkPtr _two) const =0
 Determines of the two bodies are connected by a joint.
virtual void Attach (LinkPtr _parent, LinkPtr _child)
 Attach the two bodies with this joint.
template<typename T >
event::ConnectionPtr ConnectJointUpdate (T _subscriber)
 Connect a boost::slot the the joint update signal.
virtual void Detach ()
 Detach this joint from all links.
void DisconnectJointUpdate (event::ConnectionPtr &_conn)
 Disconnect a boost::slot the the joint update signal.
void FillMsg (msgs::Joint &_msg)
 Fill a joint message.
virtual math::Vector3 GetAnchor (int _index) const =0
 Get the anchor point.
math::Angle GetAngle (int _index) const
 Get the angle of rotation of an axis(index)
virtual unsigned int GetAngleCount () const =0
 Get the angle count.
virtual double GetAttribute (const std::string &_key, unsigned int _index)=0
 Get a non-generic parameter for the joint.
LinkPtr GetChild () const
 Get the child link.
double GetDamping (int _index)
 Returns the current joint damping coefficient.
virtual double GetEffortLimit (int _index)
 Get the effort limit on axis(index).
virtual double GetForce (int _index) GAZEBO_DEPRECATED(1.5)
virtual double GetForce (unsigned int _index)
virtual JointWrench GetForceTorque (int _index) GAZEBO_DEPRECATED(1.5)=0
 get internal force and torque values at a joint Note that you must set <provide_feedback>true<provide_feedback> in the joint sdf to use this.
virtual JointWrench GetForceTorque (unsigned int _index)=0
 get internal force and torque values at a joint Note that you must set <provide_feedback>true<provide_feedback> in the joint sdf to use this.
virtual math::Vector3 GetGlobalAxis (int _index) const =0
 Get the axis of rotation in global cooridnate frame.
virtual math::Angle GetHighStop (int _index)=0
 Get the high stop of an axis(index).
double GetInertiaRatio (unsigned int _index) const
 Accessor to inertia ratio across this joint.
virtual LinkPtr GetJointLink (int _index) const =0
 Get the link to which the joint is attached according the _index.
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.
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.
math::Vector3 GetLocalAxis (int _index) const
 Get the axis of rotation.
math::Angle GetLowerLimit (unsigned int _index) const
 : get the joint upper limit (replaces GetLowStop and GetHighStop)
virtual math::Angle GetLowStop (int _index)=0
 Get the low stop of an axis(index).
virtual double GetMaxForce (int _index)=0
 Get the max allowed force of an axis(index).
LinkPtr GetParent () const
 Get the parent link.
math::Angle GetUpperLimit (unsigned int _index) const
 : get the joint lower limit (replacee GetLowStop and GetHighStop)
virtual double GetVelocity (int _index) const =0
 Get the rotation rate of an axis(index)
virtual double GetVelocityLimit (int _index)
 Get the velocity limit on axis(index).
virtual void Init ()
 Initialize a joint.
void Load (LinkPtr _parent, LinkPtr _child, const math::Pose &_pose)
 Set pose, parent and child links of a physics::Joint.
void Load (LinkPtr _parent, LinkPtr _child, const math::Vector3 &_pos) GAZEBO_DEPRECATED(1.5)
 Set parent and child links of a physics::Joint and its anchor offset position.
virtual void Load (sdf::ElementPtr _sdf)
 Load physics::Joint from a SDF sdf::Element.
virtual void Reset ()
 Reset the joint.
virtual void SetAnchor (int _index, const math::Vector3 &_anchor)=0
 Set the anchor point.
void SetAngle (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.
virtual void SetAttribute (const std::string &_key, int _index, const boost::any &_value)=0
 Set a non-generic parameter for the joint.
virtual void SetAxis (int _index, const math::Vector3 &_axis)=0
 Set the axis of rotation where axis is specified in local joint frame.
virtual void SetDamping (int _index, double _damping)=0
 Set the joint damping.
virtual void SetForce (int _index, double _force)
 Set the force applied to this physics::Joint.
virtual void SetHighStop (int _index, const math::Angle &_angle)
 Set the high stop of an axis(index).
virtual void SetLowStop (int _index, const math::Angle &_angle)
 Set the low stop of an axis(index).
virtual void SetMaxForce (int _index, double _force)=0
 Set the max allowed force of an axis(index).
void SetModel (ModelPtr _model)
 Set the model this joint belongs too.
virtual void SetProvideFeedback (bool _enable)
 Set whether the joint should generate feedback.
void SetState (const JointState &_state)
 Set the joint state.
virtual void SetVelocity (int _index, double _vel)=0
 Set the velocity of an axis(index).
void Update ()
 Update the joint.
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 Update the parameters using new sdf values.
- Public Member Functions inherited from gazebo::physics::Base
 Base (BasePtr _parent)
 Constructor.
virtual ~Base ()
 Destructor.
void AddChild (BasePtr _child)
 Add a child to this entity.
void AddType (EntityType _type)
 Add a type specifier.
virtual void Fini ()
 Finialize the object.
BasePtr GetById (unsigned int _id) const
 This is an internal function.
BasePtr GetByName (const std::string &_name)
 Get by name.
BasePtr GetChild (unsigned int _i) const
 Get a child by index.
BasePtr GetChild (const std::string &_name)
 Get a child by name.
unsigned int GetChildCount () const
 Get the number of children.
unsigned int GetId () const
 Return the ID of this entity.
std::string GetName () const
 Return the name of the entity.
int GetParentId () const
 Return the ID of the parent.
bool GetSaveable () const
 Get whether the object should be "saved", when the user selects to save the world to xml.
std::string GetScopedName () const
 Return the name of this entity with the model scope world::model1::...::modelN::entityName.
virtual const sdf::ElementPtr GetSDF ()
 Get the SDF values for the object.
unsigned int GetType () const
 Get the full type definition.
const WorldPtrGetWorld () const
 Get the World this object is in.
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type.
bool IsSelected () const
 True if the entity is selected by the user.
bool operator== (const Base &_ent) const
 Returns true if the entities are the same.
void Print (const std::string &_prefix)
 Print this object to screen via gzmsg.
virtual void RemoveChild (unsigned int _id)
 Remove a child from this entity.
void RemoveChild (const std::string &_name)
 Remove a child by name.
void RemoveChildren ()
 Remove all children.
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's.
virtual void SetName (const std::string &_name)
 Set the name of the entity.
void SetParent (BasePtr _parent)
 Set the parent.
void SetSaveable (bool _v)
 Set whether the object should be "saved", when the user selects to save the world to xml.
virtual bool SetSelected (bool _show)
 Set whether this entity has been selected by the user through the gui.
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to.

Protected Member Functions

virtual math::Angle GetAngleImpl (int _index) const =0
 Get the angle of an axis helper function.
- Protected Member Functions inherited from gazebo::physics::Base
void ComputeScopedName ()
 Compute the scoped name of this object based on its parents.

Protected Attributes

LinkPtr anchorLink
 Anchor link.
math::Vector3 anchorPos
 Anchor pose.
math::Pose anchorPose
 Anchor pose specified in SDF <joint><pose> tag.
gazebo::event::ConnectionPtr applyDamping
 apply damping for adding viscous damping forces on updates
LinkPtr childLink
 The first link this joint connects to.
double dampingCoefficient
 joint dampingCoefficient
double effortLimit [2]
 Store Joint effort limit as specified in SDF.
double forceApplied [2]
 Save force applied by user This plus the joint feedback (joint contstraint forces) is the equivalent of simulated force torque sensor reading Allocate a 2 vector in case hinge2 joint is used.
double inertiaRatio [2]
 Store Joint inertia ratio.
math::Angle lowerLimit [2]
 Store Joint position lower limit as specified in SDF.
ModelPtr model
 Pointer to the parent model.
LinkPtr parentLink
 The second link this joint connects to.
bool provideFeedback
 Provide Feedback data for contact forces.
math::Angle upperLimit [2]
 Store Joint position upper limit as specified in SDF.
bool useCFMDamping
 option to use CFM damping
double velocityLimit [2]
 Store Joint velocity limit as specified in SDF.
- Protected Attributes inherited from gazebo::physics::Base
Base_V children
 Children of this entity.
Base_V::iterator childrenEnd
 End of the children vector.
BasePtr parent
 Parent of this entity.
sdf::ElementPtr sdf
 The SDF values for this object.
WorldPtr world
 Pointer to the world.

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::ApplyDamping ( )
virtual

Callback to apply damping force to joint.

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

References gazebo::event::EventT< T >::Connect().

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

Detach this joint from all links.

void gazebo::physics::Joint::DisconnectJointUpdate ( event::ConnectionPtr _conn)
inline

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

Parameters
[in]_connConnection to disconnect.

References gazebo::event::EventT< T >::Disconnect().

void gazebo::physics::Joint::FillMsg ( msgs::Joint &  _msg)

Fill a joint message.

Parameters
[out]_msgMessage to fill with this joint's properties.
virtual math::Vector3 gazebo::physics::Joint::GetAnchor ( int  _index) const
pure virtual

Get the anchor point.

Parameters
[in]_indexIndex of the axis.
Returns
Anchor value for the axis.
math::Angle gazebo::physics::Joint::GetAngle ( 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

Get the angle count.

Returns
The number of DOF for the joint.
virtual math::Angle gazebo::physics::Joint::GetAngleImpl ( int  _index) const
protectedpure virtual

Get the angle of an axis helper function.

Parameters
[in]_indexIndex of the axis.
Returns
Angle of the axis.
virtual double gazebo::physics::Joint::GetAttribute ( const std::string &  _key,
unsigned int  _index 
)
pure virtual

Get a non-generic parameter for the joint.

Parameters
[in]_keyString key.
[in]_indexIndex of the axis.
[in]_valueValue of the attribute.
LinkPtr gazebo::physics::Joint::GetChild ( ) const

Get the child link.

Returns
Pointer to the child link.
double gazebo::physics::Joint::GetDamping ( 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 ( 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 ( int  _index)
virtual
Todo:
: not yet implemented. Get the forces applied at this Joint. Note that the unit of force should be consistent with the rest of the simulation scales. E.g. if you are using metric units, the unit for force is Newtons. If using imperial units (sorry), then unit of force is lb-force not (lb-mass), etc.
Parameters
[in]_indexIndex of the axis.
Returns
The force applied to an axis.
virtual double gazebo::physics::Joint::GetForce ( unsigned int  _index)
virtual
Todo:
: not yet implemented. Get the forces applied at this Joint. Note that the unit of force should be consistent with the rest of the simulation scales. E.g. if you are using metric units, the unit for force is Newtons. If using imperial units (sorry), then unit of force is lb-force not (lb-mass), etc.
Parameters
[in]_indexIndex of the axis.
Returns
The force applied to an axis.
virtual JointWrench gazebo::physics::Joint::GetForceTorque ( int  _index)
pure virtual

get internal force and torque values at a joint Note that you must set <provide_feedback>true<provide_feedback> in the joint sdf to use this.

Parameters
[in]_indexForce and torque on child link if _index = 0 and on parent link of _index = 1
Returns
The force and torque at the joint
virtual JointWrench gazebo::physics::Joint::GetForceTorque ( unsigned int  _index)
pure virtual

get internal force and torque values at a joint Note that you must set <provide_feedback>true<provide_feedback> in the joint sdf to use this.

Parameters
[in]_indexForce and torque on child link if _index = 0 and on parent link of _index = 1
Returns
The force and torque at the joint
virtual math::Vector3 gazebo::physics::Joint::GetGlobalAxis ( int  _index) const
pure virtual

Get the axis of rotation in global cooridnate frame.

Parameters
[in]_indexIndex of the axis to get.
Returns
Axis value for the provided index.
virtual math::Angle gazebo::physics::Joint::GetHighStop ( 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.
double gazebo::physics::Joint::GetInertiaRatio ( unsigned int  _index) const

Accessor to inertia ratio across this joint.

Parameters
[in]_indexJoint axis index.
Returns
returns the inertia ratio across specified joint axis.
virtual LinkPtr gazebo::physics::Joint::GetJointLink ( 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.
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. E.g. if you are using metric units, the unit for force is Newtons. If using imperial units (sorry), then unit of force is lb-force not (lb-mass), etc.

Parameters
[in]indexThe index of the link(0 or 1).
Returns
Force applied to the link.
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. E.g. if you are using metric units, the unit for force is Newtons-Meters. If using imperial units (sorry), then unit of force is lb-force-inches not (lb-mass-inches), etc.

Parameters
[in]indexThe index of the link(0 or 1)
Returns
Torque applied to the link.
math::Vector3 gazebo::physics::Joint::GetLocalAxis ( 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
Upper limit of the axis.
virtual math::Angle gazebo::physics::Joint::GetLowStop ( 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.
virtual double gazebo::physics::Joint::GetMaxForce ( int  _index)
pure virtual

Get the max allowed force of an axis(index).

Note that the unit of force should be consistent with the rest of the simulation scales. E.g. if you are using metric units, the unit for force is Newtons. If using imperial units (sorry), then unit of force is lb-force not (lb-mass), etc.

Parameters
[in]_indexIndex of the axis.
Returns
The maximum force.
LinkPtr gazebo::physics::Joint::GetParent ( ) const

Get the parent link.

Returns
Pointer to the parent link.

Reimplemented from gazebo::physics::Base.

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 ( int  _index) const
pure virtual

Get the rotation rate of an axis(index)

Parameters
[in]_indexIndex of the axis.
Returns
The rotaional velocity of the joint axis.
virtual double gazebo::physics::Joint::GetVelocityLimit ( 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
virtual void gazebo::physics::Joint::Init ( )
virtual

Initialize a joint.

Reimplemented from gazebo::physics::Base.

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.
void gazebo::physics::Joint::Load ( LinkPtr  _parent,
LinkPtr  _child,
const math::Vector3 _pos 
)

Set parent and child links of a physics::Joint and its anchor offset position.

This funciton is deprecated, use Load(LinkPtr _parent, LinkPtr _child, const math::Pose &_pose)

Parameters
[in]_parentParent link.
[in]_childChild link.
[in]_posJoint 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.

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

Reset the joint.

Reimplemented from gazebo::physics::Base.

virtual void gazebo::physics::Joint::SetAnchor ( int  _index,
const math::Vector3 _anchor 
)
pure virtual

Set the anchor point.

Parameters
[in]_indexIndx of the axis.
[in]_anchorAnchor value.
void gazebo::physics::Joint::SetAngle ( 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, all the conencted children Link's are moved as a result of the Joint angle setting. Dynamic Joint angle update is accomplished by calling JointController::SetJointPosition.

Parameters
[in]_indexIndex of the axis.
[in]_angleAngle to set the joint to.
virtual void gazebo::physics::Joint::SetAttribute ( const std::string &  _key,
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.
virtual void gazebo::physics::Joint::SetAxis ( int  _index,
const math::Vector3 _axis 
)
pure virtual

Set the axis of rotation where axis is specified in local joint frame.

Parameters
[in]_indexIndex of the axis to set.
[in]_axisVector in local joint frame of axis direction (must have length greater than zero).
virtual void gazebo::physics::Joint::SetDamping ( 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.
virtual void gazebo::physics::Joint::SetForce ( int  _index,
double  _force 
)
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. E.g. if you are using metric units, the unit for force is Newtons. If using imperial units (sorry), then unit of force is lb-force not (lb-mass), etc.

Parameters
[in]_indexIndex of the axis.
[in]_forceForce value.
virtual void gazebo::physics::Joint::SetHighStop ( int  _index,
const math::Angle _angle 
)
virtual

Set the high stop of an axis(index).

Parameters
[in]_indexIndex of the axis.
[in]_angleHigh stop angle.
virtual void gazebo::physics::Joint::SetLowStop ( int  _index,
const math::Angle _angle 
)
virtual

Set the low stop of an axis(index).

Parameters
[in]_indexIndex of the axis.
[in]_angleLow stop angle.
virtual void gazebo::physics::Joint::SetMaxForce ( int  _index,
double  _force 
)
pure virtual

Set the max allowed force of an axis(index).

Note that the unit of force should be consistent with the rest of the simulation scales. E.g. if you are using metric units, the unit for force is Newtons. If using imperial units (sorry), then unit of force is lb-force not (lb-mass), etc.

Parameters
[in]_indexIndex of the axis.
[in]_forceMaximum force that can be applied to the axis.
void gazebo::physics::Joint::SetModel ( ModelPtr  _model)

Set the model this joint belongs too.

Parameters
[in]_modelPointer to a model.
virtual void gazebo::physics::Joint::SetProvideFeedback ( bool  _enable)
virtual

Set whether the joint should generate feedback.

Parameters
[in]_enableTrue to enable joint feedback.
void gazebo::physics::Joint::SetState ( const JointState _state)

Set the joint state.

Parameters
[in]_stateJoint state
virtual void gazebo::physics::Joint::SetVelocity ( int  _index,
double  _vel 
)
pure virtual

Set the velocity of an axis(index).

Parameters
[in]_indexIndex of the axis.
[in]_velVelocity.
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

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

The first link this joint connects to.

double gazebo::physics::Joint::dampingCoefficient
protected

joint dampingCoefficient

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

Store Joint effort limit as specified in SDF.

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

Save force applied by user This plus the joint feedback (joint contstraint forces) is the equivalent of simulated force torque sensor reading Allocate a 2 vector in case hinge2 joint is used.

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

Store Joint inertia ratio.

This is a measure of how well this model behaves using interative LCP solvers.

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.

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.

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

Store Joint position upper limit as specified in SDF.

bool gazebo::physics::Joint::useCFMDamping
protected

option to use CFM damping

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

Store Joint velocity limit as specified in SDF.


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