Base class for all joints. More...
#include <physics/physics.hh>
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, TRIMESH_SHAPE = 0x00400000 } |
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. | |
virtual double | GetEffortLimit (int _index) |
Get the effort limit on axis(index). | |
virtual double | GetForce (int _index) GAZEBO_DEPRECATED |
virtual double | GetForce (unsigned int _index) |
virtual JointWrench | GetForceTorque (int _index) GAZEBO_DEPRECATED=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 |
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. | |
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. | |
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. | |
BasePtr | GetParent () const |
Get the parent. | |
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 WorldPtr & | GetWorld () 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 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. | |
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. | |
Base class for all joints.
Joint attribute types.
|
virtual |
Destructor.
|
virtual |
Callback to apply damping force to joint.
Determines of the two bodies are connected by a joint.
[in] | _one | First link. |
[in] | _two | Second link. |
Attach the two bodies with this joint.
[in] | _parent | Parent link. |
[in] | _child | Child link. |
|
inline |
Connect a boost::slot the the joint update signal.
[in] | _subscriber | Callback for the connection. |
References gazebo::event::EventT< T >::Connect().
|
virtual |
Detach this joint from all links.
|
inline |
Disconnect a boost::slot the the joint update signal.
[in] | _conn | Connection to disconnect. |
References gazebo::event::EventT< T >::Disconnect().
void gazebo::physics::Joint::FillMsg | ( | msgs::Joint & | _msg | ) |
Fill a joint message.
[out] | _msg | Message to fill with this joint's properties. |
|
pure virtual |
Get the anchor point.
[in] | _index | Index of the axis. |
math::Angle gazebo::physics::Joint::GetAngle | ( | int | _index | ) | const |
Get the angle of rotation of an axis(index)
[in] | _index | Index of the axis. |
|
pure virtual |
Get the angle count.
Referenced by GetLowerLimit(), and GetUpperLimit().
|
protectedpure virtual |
Get the angle of an axis helper function.
[in] | _index | Index of the axis. |
|
pure virtual |
Get a non-generic parameter for the joint.
[in] | _key | String key. |
[in] | _index | Index of the axis. |
[in] | _value | Value of the attribute. |
LinkPtr gazebo::physics::Joint::GetChild | ( | ) | const |
Get the child link.
|
virtual |
Get the effort limit on axis(index).
[in] | _index | Index of axis, where 0=first axis and 1=second axis |
|
virtual |
[in] | _index | Index of the axis. |
|
virtual |
[in] | _index | Index of the axis. |
|
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.
[in] | _index | Force and torque on child link if _index = 0 and on parent link of _index = 1 |
|
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.
[in] | _index | Force and torque on child link if _index = 0 and on parent link of _index = 1 |
|
pure virtual |
Get the axis of rotation in global cooridnate frame.
[in] | _index | Index of the axis to get. |
|
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)
[in] | _index | Index of the axis. |
double gazebo::physics::Joint::GetInertiaRatio | ( | unsigned int | _index | ) | const |
Accessor to inertia ratio across this joint.
[in] | _index | Joint axis index. |
|
pure virtual |
Get the link to which the joint is attached according the _index.
[in] | _index | Index of the link to retreive. |
|
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.
[in] | index | The index of the link(0 or 1). |
|
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.
[in] | index | The index of the link(0 or 1) |
math::Vector3 gazebo::physics::Joint::GetLocalAxis | ( | int | _index | ) | const |
Get the axis of rotation.
[in] | _index | Index of the axis to get. |
|
inline |
: get the joint upper limit (replaces GetLowStop and GetHighStop)
[in] | _index | Index of the axis. |
References GetAngleCount(), gzwarn, and lowerLimit.
|
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)
[in] | _index | Index of the axis. |
|
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.
[in] | _index | Index of the axis. |
LinkPtr gazebo::physics::Joint::GetParent | ( | ) | const |
Get the parent link.
|
inline |
: get the joint lower limit (replacee GetLowStop and GetHighStop)
[in] | _index | Index of the axis. |
References GetAngleCount(), gzwarn, and upperLimit.
|
pure virtual |
Get the rotation rate of an axis(index)
[in] | _index | Index of the axis. |
|
virtual |
Get the velocity limit on axis(index).
[in] | _index | Index of axis, where 0=first axis and 1=second axis |
|
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.
[in] | _parent | Parent link. |
[in] | _child | Child link. |
[in] | _pose | Pose 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)
[in] | _parent | Parent link. |
[in] | _child | Child link. |
[in] | _pos | Joint Anchor offset from child link. |
|
virtual |
Load physics::Joint from a SDF sdf::Element.
[in] | _sdf | SDF values to load from. |
Reimplemented from gazebo::physics::Base.
|
virtual |
Reset the joint.
Reimplemented from gazebo::physics::Base.
|
pure virtual |
Set the anchor point.
[in] | _index | Indx of the axis. |
[in] | _anchor | Anchor 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.
[in] | _index | Index of the axis. |
[in] | _angle | Angle to set the joint to. |
|
pure virtual |
Set a non-generic parameter for the joint.
replaces SetAttribute(Attribute, int, double)
[in] | _key | String key. |
[in] | _index | Index of the axis. |
[in] | _value | Value of the attribute. |
|
pure virtual |
Set the axis of rotation.
[in] | _index | Index of the axis to set. |
[in] | _axis | Vector in world frame of axis direction (must have length greater than zero). |
|
pure virtual |
Set the joint damping.
[in] | _index | Index of the axis to set. |
[in] | _damping | Damping value for the axis. |
|
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.
[in] | _index | Index of the axis. |
[in] | _force | Force value. |
|
virtual |
Set the high stop of an axis(index).
[in] | _index | Index of the axis. |
[in] | _angle | High stop angle. |
|
virtual |
Set the low stop of an axis(index).
[in] | _index | Index of the axis. |
[in] | _angle | Low stop angle. |
|
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.
[in] | _index | Index of the axis. |
[in] | _force | Maximum force that can be applied to the axis. |
void gazebo::physics::Joint::SetModel | ( | ModelPtr | _model | ) |
Set the model this joint belongs too.
[in] | _model | Pointer to a model. |
void gazebo::physics::Joint::SetState | ( | const JointState & | _state | ) |
Set the joint state.
[in] | _state | Joint state |
|
pure virtual |
Set the velocity of an axis(index).
[in] | _index | Index of the axis. |
[in] | _vel | Velocity. |
|
virtual |
Update the joint.
Reimplemented from gazebo::physics::Base.
|
virtual |
Update the parameters using new sdf values.
[in] | _sdf | SDF values to update from. |
Reimplemented from gazebo::physics::Base.
|
protected |
Anchor link.
|
protected |
Anchor pose.
This is the xyz offset of the joint frame from child frame specified in the parent link frame
|
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).
|
protected |
apply damping for adding viscous damping forces on updates
|
protected |
The first link this joint connects to.
|
protected |
joint dampingCoefficient
|
protected |
Store Joint effort limit as specified in SDF.
|
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.
|
protected |
Store Joint inertia ratio.
This is a measure of how well this model behaves using interative LCP solvers.
|
protected |
Store Joint position lower limit as specified in SDF.
Referenced by GetLowerLimit().
|
protected |
Pointer to the parent model.
|
protected |
The second link this joint connects to.
|
protected |
Store Joint position upper limit as specified in SDF.
Referenced by GetUpperLimit().
|
protected |
option to use CFM damping
|
protected |
Store Joint velocity limit as specified in SDF.