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

SimbodyBallJoint class models a ball joint in Simbody. More...

#include <SimbodyBallJoint.hh>

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

Public Member Functions

 SimbodyBallJoint (SimTK::MultibodySystem *_world, BasePtr _parent)
 Simbody Ball Joint Constructor. More...
 
virtual ~SimbodyBallJoint ()
 Destructor. More...
 
math::Vector3 GetAnchor (unsigned int _index) const
 Get the anchor point. More...
 
virtual math::Angle GetAngleImpl (unsigned int _index) const
 Get the angle of an axis helper function. More...
 
virtual math::Vector3 GetAxis (unsigned int) const
 
virtual math::Vector3 GetGlobalAxis (unsigned int _index) const
 Get the axis of rotation in global cooridnate frame. More...
 
virtual math::Angle GetHighStop (unsigned int _index)
 Get the high stop of an axis(index). More...
 
virtual math::Angle GetLowStop (unsigned int _index)
 Get the low stop of an axis(index). More...
 
virtual double GetMaxForce (unsigned int _index)
 Get the max allowed force of an axis(index) when using Joint::SetVelocity. More...
 
virtual double GetVelocity (unsigned int _index) const
 Get the rotation rate of an axis(index) More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load physics::Joint from a SDF sdf::Element. More...
 
virtual void SetAxis (unsigned int _index, const math::Vector3 &_axis)
 Set the axis of rotation where axis is specified in local joint frame. More...
 
virtual bool SetHighStop (unsigned int _index, const math::Angle &_angle)
 Set the high stop of an axis(index). 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 _t)
 Set the max allowed force of an axis(index) when using Joint::SetVelocity. More...
 
virtual void SetVelocity (unsigned int _index, double _angle)
 Set the velocity of an axis(index). More...
 
- Public Member Functions inherited from gazebo::physics::BallJoint< SimbodyJoint >
 BallJoint (BasePtr _parent)
 Constructor. More...
 
virtual ~BallJoint ()
 Destructor. More...
 
virtual unsigned int GetAngleCount () const
 
void Load (sdf::ElementPtr _sdf)
 Template to ::Load the BallJoint. More...
 
- Public Member Functions inherited from gazebo::physics::SimbodyJoint
 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 double GetForce (unsigned int _index)
 
virtual JointWrench GetForceTorque (unsigned int _index)
 get internal force and torque values at a joint. More...
 
virtual LinkPtr GetJointLink (unsigned 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 double GetParam (const std::string &_key, unsigned int _index)
 Get a non-generic parameter for the joint. More...
 
virtual void Reset ()
 Reset the joint. More...
 
virtual void RestoreSimbodyState (SimTK::State &_state)
 
virtual void SaveSimbodyState (const SimTK::State &_state)
 
virtual void SetAnchor (unsigned int _index, const gazebo::math::Vector3 &_anchor)
 Set the anchor point. More...
 
virtual void SetAttribute (Attribute, unsigned int _index, double _value)
 Set a parameter for the joint. More...
 
virtual void SetDamping (unsigned int _index, const double _damping)
 Set the joint damping. More...
 
virtual void SetForce (unsigned int _index, double _force)
 Set the force applied to this physics::Joint. More...
 
virtual bool SetParam (const std::string &_key, unsigned int _index, const boost::any &_value)
 Set a non-generic parameter for the joint. More...
 
virtual void SetStiffness (unsigned int _index, const double _stiffness)
 Set the joint spring stiffness. More...
 
virtual void SetStiffnessDamping (unsigned int _index, double _stiffness, double _damping, double _reference=0)
 Set the joint spring stiffness. More...
 
- Public Member Functions inherited from gazebo::physics::Joint
 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 void Attach (LinkPtr _parent, LinkPtr _child)
 Attach the two bodies with this joint. 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...
 
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...
 
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...
 
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...
 
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...
 
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...
 
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 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...
 
void Load (LinkPtr _parent, LinkPtr _child, const math::Pose &_pose)
 Set pose, parent and child links of a physics::Joint. 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 SetEffortLimit (unsigned int _index, double _effort)
 Set the effort limit on a joint axis. More...
 
void SetLowerLimit (unsigned int _index, math::Angle _limit)
 : set the joint upper limit (replaces SetLowStop and SetHighStop) More...
 
void SetModel (ModelPtr _model)
 Set the model this joint belongs too. 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...
 
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...
 
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

virtual void SetForceImpl (unsigned int _index, double _torque)
 Set the force applied to this physics::Joint. More...
 
- Protected Member Functions inherited from gazebo::physics::BallJoint< SimbodyJoint >
virtual void Init ()
 Initialize joint. More...
 
- Protected Member Functions inherited from gazebo::physics::Joint
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...
 
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...
 

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...
 
- 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 Attributes inherited from gazebo::physics::SimbodyJoint
SimTK::Constraint constraint
 : isValid() if we used a constraint to model this joint. More...
 
SimTK::Force::MobilityLinearDamper damper [MAX_JOINT_AXIS]
 : 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 [MAX_JOINT_AXIS]
 : 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::Force::MobilityLinearSpring spring [MAX_JOINT_AXIS]
 : Spring force element for enforcing joint stiffness. More...
 
SimTK::Transform xCB
 child body frame to mobilizer frame More...
 
SimTK::Transform xPA
 Normally A=F, B=M. More...
 
- Protected Attributes inherited from gazebo::physics::SimbodyJoint
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...
 
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

SimbodyBallJoint class models a ball joint in Simbody.

Constructor & Destructor Documentation

gazebo::physics::SimbodyBallJoint::SimbodyBallJoint ( SimTK::MultibodySystem *  _world,
BasePtr  _parent 
)

Simbody Ball Joint Constructor.

virtual gazebo::physics::SimbodyBallJoint::~SimbodyBallJoint ( )
virtual

Destructor.

Member Function Documentation

math::Vector3 gazebo::physics::SimbodyBallJoint::GetAnchor ( unsigned int  _index) const
virtual

Get the anchor point.

Parameters
[in]_indexIndex of the axis.
Returns
Anchor value for the axis.

Reimplemented from gazebo::physics::SimbodyJoint.

virtual math::Angle gazebo::physics::SimbodyBallJoint::GetAngleImpl ( unsigned int  _index) const
virtual

Get the angle of an axis helper function.

Parameters
[in]_indexIndex of the axis.
Returns
Angle of the axis.

Implements gazebo::physics::Joint.

virtual math::Vector3 gazebo::physics::SimbodyBallJoint::GetAxis ( unsigned  int) const
inlinevirtual
virtual math::Vector3 gazebo::physics::SimbodyBallJoint::GetGlobalAxis ( unsigned int  _index) const
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.

Implements gazebo::physics::Joint.

virtual math::Angle gazebo::physics::SimbodyBallJoint::GetHighStop ( unsigned int  _index)
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.

Reimplemented from gazebo::physics::SimbodyJoint.

virtual math::Angle gazebo::physics::SimbodyBallJoint::GetLowStop ( unsigned int  _index)
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.

Reimplemented from gazebo::physics::SimbodyJoint.

virtual double gazebo::physics::SimbodyBallJoint::GetMaxForce ( unsigned int  _index)
virtual

Get the max allowed force of an axis(index) when using Joint::SetVelocity.

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

Parameters
[in]_indexIndex of the axis.
Returns
The maximum force.

Implements gazebo::physics::Joint.

virtual double gazebo::physics::SimbodyBallJoint::GetVelocity ( unsigned int  _index) const
virtual

Get the rotation rate of an axis(index)

Parameters
[in]_indexIndex of the axis.
Returns
The rotaional velocity of the joint axis.

Implements gazebo::physics::Joint.

virtual void gazebo::physics::SimbodyBallJoint::Load ( sdf::ElementPtr  _sdf)
virtual

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

Parameters
[in]_sdfSDF values to load from.

Reimplemented from gazebo::physics::SimbodyJoint.

virtual void gazebo::physics::SimbodyBallJoint::SetAxis ( unsigned 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).

Reimplemented from gazebo::physics::SimbodyJoint.

virtual void gazebo::physics::SimbodyBallJoint::SetForceImpl ( unsigned int  _index,
double  _force 
)
protectedvirtual

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.

Implements gazebo::physics::SimbodyJoint.

virtual bool gazebo::physics::SimbodyBallJoint::SetHighStop ( unsigned 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.

Reimplemented from gazebo::physics::SimbodyJoint.

virtual bool gazebo::physics::SimbodyBallJoint::SetLowStop ( unsigned 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.

Reimplemented from gazebo::physics::SimbodyJoint.

virtual void gazebo::physics::SimbodyBallJoint::SetMaxForce ( unsigned int  _index,
double  _force 
)
virtual

Set the max allowed force of an axis(index) when using Joint::SetVelocity.

Current implementation in Bullet and ODE is enforced using impulses, which enforces force/torque limits when calling Joint::SetVelocity. Current implementation is engine dependent. See for example ODE implementation in ODEHingeJoint::SetMaxForce. Note this functionality is not implemented in DART and Simbody. Note that the unit of force should be consistent with the rest of the simulation scales.

Parameters
[in]_indexIndex of the axis.
[in]_forceMaximum force that can be applied to the axis.

Implements gazebo::physics::Joint.

virtual void gazebo::physics::SimbodyBallJoint::SetVelocity ( unsigned int  _index,
double  _vel 
)
virtual

Set the velocity of an axis(index).

Parameters
[in]_indexIndex of the axis.
[in]_velVelocity.

Implements gazebo::physics::Joint.


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