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

Base class for all joints. More...

#include <SimbodyJoint.hh>

Inheritance diagram for gazebo::physics::SimbodyJoint:
Inheritance graph
[legend]

Public Member Functions

 SimbodyJoint (BasePtr _parent)
 Constructor. More...
 
virtual ~SimbodyJoint ()
 Destructor. More...
 
virtual bool AreConnected (LinkPtr _one, LinkPtr _two) const
 Determines of the two bodies are connected by a joint. More...
 
virtual void CacheForceTorque ()
 Cache Joint Force Torque Values if necessary for physics engine. More...
 
virtual void Detach ()
 Detach this joint from all links. More...
 
virtual math::Vector3 GetAnchor (int _index) const
 Get the anchor point. More...
 
virtual double GetAttribute (const std::string &_key, unsigned int _index)
 Get a non-generic parameter for the joint. More...
 
virtual double GetForce (unsigned int _index)
 
virtual JointWrench GetForceTorque (unsigned int _index)
 get internal force and torque values at a joint. More...
 
virtual LinkPtr GetJointLink (int _index) const
 Get the link to which the joint is attached according the _index. More...
 
virtual math::Vector3 GetLinkForce (unsigned int _index) const
 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
 Get the torque applied to the center of mass of a physics::Link due to the existence of this 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 RestoreSimbodyState (SimTK::State &_state)
 
virtual void SaveSimbodyState (const SimTK::State &_state)
 
virtual void SetAnchor (int _index, const gazebo::math::Vector3 &_anchor)
 Set the anchor point. More...
 
virtual void SetAttribute (Attribute, int _index, double _value)
 Set a parameter for the joint. More...
 
virtual void SetAttribute (const std::string &_key, int _index, const boost::any &_value)
 Set a non-generic parameter for the joint. More...
 
virtual void SetAxis (int _index, const math::Vector3 &_axis)
 Set the axis of rotation where axis is specified in local joint frame. More...
 
virtual void SetDamping (int _index, const double _damping)
 Set the joint damping. More...
 
virtual void SetForce (int _index, double _force)
 Set the force applied to this physics::Joint. More...
 
- Public Member Functions inherited from gazebo::physics::Joint
 Joint (BasePtr _parent)
 Constructor. More...
 
virtual ~Joint ()
 Destructor. More...
 
virtual void ApplyDamping ()
 Callback to apply damping force to joint. More...
 
virtual void Attach (LinkPtr _parent, LinkPtr _child)
 Attach the two bodies with this joint. More...
 
double CheckAndTruncateForce (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...
 
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...
 
math::Angle GetAngle (int _index) const
 Get the angle of rotation of an axis(index) More...
 
virtual unsigned int GetAngleCount () const =0
 Get the angle count. More...
 
LinkPtr GetChild () const
 Get the child link. More...
 
double GetDamping (int _index)
 Returns the current joint damping coefficient. More...
 
double GetDampingCoefficient () const
 Get damping coefficient of this joint. More...
 
virtual double GetEffortLimit (int _index)
 Get the effort limit on axis(index). More...
 
virtual math::Vector3 GetGlobalAxis (int _index) const =0
 Get the axis of rotation in global cooridnate frame. More...
 
virtual math::Angle GetHighStop (int _index)=0
 Get the high stop of an axis(index). More...
 
double GetInertiaRatio (unsigned int _index) const
 Accessor to inertia ratio across this joint. More...
 
math::Pose GetInitialAnchorPose ()
 Get initial Anchor Pose specified by model <joint><pose>...</pose></joint> More...
 
math::Vector3 GetLocalAxis (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 (int _index)=0
 Get the low stop of an axis(index). More...
 
virtual double GetMaxForce (int _index)=0
 Get the max allowed force of an axis(index). More...
 
LinkPtr GetParent () const
 Get the parent link. More...
 
math::Angle GetUpperLimit (unsigned int _index) const
 : get the joint lower limit (replacee GetLowStop and GetHighStop) More...
 
virtual double GetVelocity (int _index) const =0
 Get the rotation rate of an axis(index) More...
 
virtual double GetVelocityLimit (int _index)
 Get the velocity limit on axis(index). 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...
 
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. More...
 
virtual void SetEffortLimit (unsigned int _index, double _effort)
 Set the effort limit on a joint axis. More...
 
virtual void SetHighStop (int _index, const math::Angle &_angle)
 Set the high stop of an axis(index). More...
 
virtual void SetLowStop (int _index, const math::Angle &_angle)
 Set the low stop of an axis(index). More...
 
virtual void SetMaxForce (int _index, double _force)=0
 Set the max allowed force of an axis(index). More...
 
void SetModel (ModelPtr _model)
 Set the model this joint belongs too. 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 SetVelocity (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...
 
virtual void Fini ()
 Finialize the object. 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 () const
 Return the name of this entity with the model scope world::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...
 

Public Attributes

SimTK::Constraint constraint
 : isValid() if we used a constraint to model this joint. More...
 
SimTK::Force::MobilityLinearDamper damper
 : for enforcing joint damping forces. More...
 
SimTK::Transform defxAB
 default mobilizer pose More...
 
bool isReversed
 : if mobilizer, did it reverse parent&child? Set when we build the Simbody model. More...
 
SimTK::Force::MobilityLinearStop limitForce
 : for enforcing joint stops Set when we build the Simbody model. More...
 
SimTK::MobilizedBody mobod
 Use isValid() if we used a mobilizer Set when we build the Simbody model. More...
 
bool mustBreakLoopHere
 Force Simbody to break a loop by using a weld constraint. More...
 
bool physicsInitialized
 
SimTK::Transform xCB
 child body frame to mobilizer frame More...
 
SimTK::Transform xPA
 Normally A=F, B=M. More...
 

Protected Member Functions

virtual void SetForceImpl (int _index, double _force)=0
 Set the force applied to this physics::Joint. More...
 
- Protected Member Functions inherited from gazebo::physics::Joint
virtual math::Angle GetAngleImpl (int _index) const =0
 Get the angle of an axis helper function. 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

SimbodyPhysicsPtr simbodyPhysics
 keep a pointer to the simbody physics engine for convenience More...
 
SimTK::MultibodySystem * world
 Simbody Multibody System. More...
 
- Protected Attributes inherited from gazebo::physics::Joint
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...
 
LinkPtr childLink
 The first link this joint connects to. More...
 
double dampingCoefficient
 joint dampingCoefficient More...
 
double effortLimit [2]
 Store Joint effort limit as specified in SDF. More...
 
double inertiaRatio [2]
 Store Joint inertia ratio. More...
 
math::Angle lowerLimit [2]
 Store Joint position lower limit as specified in SDF. More...
 
ModelPtr model
 Pointer to the parent model. More...
 
LinkPtr parentLink
 The second link this joint connects to. More...
 
bool provideFeedback
 Provide Feedback data for contact forces. More...
 
math::Angle upperLimit [2]
 Store Joint position upper limit as specified in SDF. More...
 
bool useCFMDamping
 option to use CFM damping 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...
 
Base_V::iterator childrenEnd
 End of the children vector. 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...
 

Additional Inherited Members

- Public Types inherited from gazebo::physics::Joint
enum  Attribute {
  FUDGE_FACTOR, SUSPENSION_ERP, SUSPENSION_CFM, STOP_ERP,
  STOP_CFM, ERP, CFM, FMAX,
  VEL, HI_STOP, LO_STOP
}
 Joint attribute types. More...
 

Detailed Description

Base class for all joints.

Constructor & Destructor Documentation

gazebo::physics::SimbodyJoint::SimbodyJoint ( BasePtr  _parent)

Constructor.

virtual gazebo::physics::SimbodyJoint::~SimbodyJoint ( )
virtual

Destructor.

Member Function Documentation

virtual bool gazebo::physics::SimbodyJoint::AreConnected ( LinkPtr  _one,
LinkPtr  _two 
) const
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.

Implements gazebo::physics::Joint.

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

Cache Joint Force Torque Values if necessary for physics engine.

Reimplemented from gazebo::physics::Joint.

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

Detach this joint from all links.

Reimplemented from gazebo::physics::Joint.

virtual math::Vector3 gazebo::physics::SimbodyJoint::GetAnchor ( int  _index) const
virtual
virtual double gazebo::physics::SimbodyJoint::GetAttribute ( const std::string &  _key,
unsigned int  _index 
)
virtual

Get a non-generic parameter for the joint.

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

Implements gazebo::physics::Joint.

virtual double gazebo::physics::SimbodyJoint::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 from gazebo::physics::Joint.

virtual JointWrench gazebo::physics::SimbodyJoint::GetForceTorque ( unsigned int  _index)
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.

Implements gazebo::physics::Joint.

virtual LinkPtr gazebo::physics::SimbodyJoint::GetJointLink ( int  _index) const
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.

Implements gazebo::physics::Joint.

virtual math::Vector3 gazebo::physics::SimbodyJoint::GetLinkForce ( unsigned int  _index) const
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.

Implements gazebo::physics::Joint.

virtual math::Vector3 gazebo::physics::SimbodyJoint::GetLinkTorque ( unsigned int  _index) const
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.

Implements gazebo::physics::Joint.

virtual void gazebo::physics::SimbodyJoint::Load ( sdf::ElementPtr  _sdf)
virtual
virtual void gazebo::physics::SimbodyJoint::Reset ( )
virtual

Reset the joint.

Reimplemented from gazebo::physics::Joint.

virtual void gazebo::physics::SimbodyJoint::RestoreSimbodyState ( SimTK::State &  _state)
virtual
virtual void gazebo::physics::SimbodyJoint::SaveSimbodyState ( const SimTK::State &  _state)
virtual
virtual void gazebo::physics::SimbodyJoint::SetAnchor ( int  _index,
const gazebo::math::Vector3 _anchor 
)
virtual

Set the anchor point.

Parameters
[in]_indexIndx of the axis.
[in]_anchorAnchor value.

Implements gazebo::physics::Joint.

Reimplemented in gazebo::physics::ScrewJoint< SimbodyJoint >, and gazebo::physics::SliderJoint< SimbodyJoint >.

virtual void gazebo::physics::SimbodyJoint::SetAttribute ( Attribute  ,
int  _index,
double  _value 
)
virtual

Set a parameter for the joint.

virtual void gazebo::physics::SimbodyJoint::SetAttribute ( const std::string &  _key,
int  _index,
const boost::any &  _value 
)
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.

Implements gazebo::physics::Joint.

virtual void gazebo::physics::SimbodyJoint::SetAxis ( int  _index,
const math::Vector3 _axis 
)
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).

Implements gazebo::physics::Joint.

Reimplemented in gazebo::physics::BallJoint< SimbodyJoint >, gazebo::physics::SimbodyHinge2Joint, gazebo::physics::SimbodyUniversalJoint, gazebo::physics::SimbodyScrewJoint, gazebo::physics::SimbodyHingeJoint, and gazebo::physics::SimbodySliderJoint.

virtual void gazebo::physics::SimbodyJoint::SetDamping ( int  _index,
const double  _damping 
)
virtual

Set the joint damping.

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

Implements gazebo::physics::Joint.

Reimplemented in gazebo::physics::SimbodySliderJoint, gazebo::physics::SimbodyUniversalJoint, gazebo::physics::SimbodyHinge2Joint, gazebo::physics::SimbodyHingeJoint, gazebo::physics::SimbodyScrewJoint, and gazebo::physics::SimbodyBallJoint.

virtual void gazebo::physics::SimbodyJoint::SetForce ( int  _index,
double  _effort 
)
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.

Implements gazebo::physics::Joint.

virtual void gazebo::physics::SimbodyJoint::SetForceImpl ( int  _index,
double  _force 
)
protectedpure 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 SetForceImpl to the same joint in the same time step will accumulate forces on that Joint).

Parameters
[in]_indexIndex of the axis.
[in]_forceForce value. internal force, e.g. damping forces. This way, Joint::appliedForce keep track of external forces only.

Implemented in gazebo::physics::SimbodyHinge2Joint, gazebo::physics::SimbodyUniversalJoint, gazebo::physics::SimbodyScrewJoint, gazebo::physics::SimbodyHingeJoint, gazebo::physics::SimbodySliderJoint, and gazebo::physics::SimbodyBallJoint.

Member Data Documentation

SimTK::Constraint gazebo::physics::SimbodyJoint::constraint

: isValid() if we used a constraint to model this joint.

Set when we build the Simbody model. How this joint was modeled in the Simbody System. We used either a mobilizer or a constraint, but not both. The type of either one is the same as the joint type above.

SimTK::Force::MobilityLinearDamper gazebo::physics::SimbodyJoint::damper

: for enforcing joint damping forces.

Set when we build the Simbody model. : Make these arrays for multi-axis joints. : Also, consider moving this into individual joint type subclass so we can specify custom dampers for special joints like ball joints.

SimTK::Transform gazebo::physics::SimbodyJoint::defxAB

default mobilizer pose

bool gazebo::physics::SimbodyJoint::isReversed

: if mobilizer, did it reverse parent&child? Set when we build the Simbody model.

SimTK::Force::MobilityLinearStop gazebo::physics::SimbodyJoint::limitForce

: for enforcing joint stops Set when we build the Simbody model.

: Make these arrays for multi-axis joints. : Also, consider moving this into individual joint type subclass so we can specify custom dampers for special joints like ball joints.

SimTK::MobilizedBody gazebo::physics::SimbodyJoint::mobod

Use isValid() if we used a mobilizer Set when we build the Simbody model.

How this joint was modeled in the Simbody System. We used either a mobilizer or a constraint, but not both. The type of either one is the same as the joint type above.

bool gazebo::physics::SimbodyJoint::mustBreakLoopHere

Force Simbody to break a loop by using a weld constraint.

This flag is needed by SimbodyPhysics::MultibodyGraphMaker, so kept public.

bool gazebo::physics::SimbodyJoint::physicsInitialized
SimbodyPhysicsPtr gazebo::physics::SimbodyJoint::simbodyPhysics
protected

keep a pointer to the simbody physics engine for convenience

SimTK::MultibodySystem* gazebo::physics::SimbodyJoint::world
protected

Simbody Multibody System.

SimTK::Transform gazebo::physics::SimbodyJoint::xCB

child body frame to mobilizer frame

SimTK::Transform gazebo::physics::SimbodyJoint::xPA

Normally A=F, B=M.

But if reversed, then B=F, A=M. parent body frame to mobilizer frame


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