BulletFixedJoint Class Reference

A fixed joint. More...

#include <BulletFixedJoint.hh>

Inherits FixedJoint< BulletJoint >.

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...
 
enum  EntityType {
  BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004,
  COLLISION = 0x00000008, 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, FIXED_JOINT = 0x00004000,
  ACTOR = 0x00008000, SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000,
  HEIGHTMAP_SHAPE = 0x00080000, MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000,
  PLANE_SHAPE = 0x00800000, SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000,
  SENSOR_COLLISION = 0x10000000
}
 Unique identifiers for all entity types. More...
 

Public Member Functions

 BulletFixedJoint (btDynamicsWorld *world, BasePtr _parent)
 Constructor. More...
 
virtual ~BulletFixedJoint ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
virtual ignition::math::Vector3d Anchor (const unsigned int _index) const
 Get the anchor point. More...
 
ignition::math::Pose3d AnchorErrorPose () const
 Get pose offset between anchor pose on child and parent, expressed in the parent link frame. More...
 
virtual void ApplyStiffnessDamping ()
 Callback to apply spring stiffness and viscous damping effects to joint. More...
 
bool AreConnected (LinkPtr _one, LinkPtr _two) const
 Determines of the two bodies are connected by a joint. More...
 
virtual void Attach (LinkPtr _parent, LinkPtr _child)
 Attach the two bodies with this joint. More...
 
ignition::math::Quaterniond AxisFrame (const unsigned int _index) const
 Get orientation of reference frame for specified axis, relative to world frame. More...
 
ignition::math::Quaterniond AxisFrameOffset (const unsigned int _index) const
 Get orientation of joint axis reference frame relative to joint frame. More...
 
virtual void CacheForceTorque ()
 Cache Joint Force Torque Values if necessary for physics engine. More...
 
double CheckAndTruncateForce (unsigned int _index, double _effort)
 check if the force against velocityLimit and effortLimit, truncate if necessary. More...
 
template<typename T >
event::ConnectionPtr ConnectJointUpdate (T _subscriber)
 Connect a boost::slot the the joint update signal. More...
 
virtual void Detach ()
 Detach this joint from all bodies. More...
 
virtual unsigned int DOF () const
 
virtual void FillMsg (msgs::Joint &_msg)
 Fill a joint message. 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...
 
LinkPtr GetChild () const
 Get the child link. More...
 
unsigned int GetChildCount () const
 Get the number of children. More...
 
double GetDamping (unsigned int _index)
 Returns the current joint damping coefficient. More...
 
virtual double GetEffortLimit (unsigned int _index)
 Get the effort limit on axis(index). More...
 
virtual double GetForce (unsigned int _index)
 
virtual JointWrench GetForceTorque (unsigned int _index)
 get internal force and torque values at a joint. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
double GetInertiaRatio (const unsigned int _index) const
 Computes moment of inertia (MOI) across a specified joint axis. More...
 
LinkPtr GetJointLink (unsigned int _index) const
 Get the body to which the joint is attached according the _index. More...
 
msgs::Joint::Type GetMsgType () const
 Get the joint type as msgs::Joint::Type. More...
 
std::string GetName () const
 Return the name of the entity. More...
 
virtual double GetParam (const std::string &_key, unsigned int _index)
 Get a non-generic parameter for the joint. More...
 
LinkPtr GetParent () const
 Get the parent link. 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...
 
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...
 
unsigned int GetType () const
 Get the full type definition. More...
 
virtual double GetVelocity (unsigned int _index) const
 Get the rotation rate of an axis(index) More...
 
virtual double GetVelocityLimit (unsigned int _index)
 Get the velocity limit on axis(index). More...
 
const WorldPtrGetWorld () const
 Get the World this object is in. More...
 
double GetWorldEnergyPotentialSpring (unsigned int _index) const
 Returns this joint's spring potential energy, based on the reference position of the spring. More...
 
virtual ignition::math::Vector3d GlobalAxis (const unsigned int _index) const
 Get the axis of rotation in global cooridnate frame. More...
 
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type. More...
 
double InertiaRatio (const ignition::math::Vector3d &_axis) const
 Computes moment of inertia (MOI) across an arbitrary axis specified in the world frame. More...
 
virtual void Init ()
 Initialize joint. More...
 
ignition::math::Pose3d InitialAnchorPose () const
 Get initial Anchor Pose specified by model <joint><pose>...</pose></joint> More...
 
bool IsSelected () const
 True if the entity is selected by the user. More...
 
virtual ignition::math::Vector3d LinkForce (const unsigned int _index) const
 Get the force the joint applies to the first body. More...
 
virtual ignition::math::Vector3d LinkTorque (const unsigned int _index) const
 Get the torque the joint applies to the first body. More...
 
void Load (LinkPtr _parent, LinkPtr _child, const ignition::math::Pose3d &_pose)
 Set pose, parent and child links of a physics::Joint. More...
 
ignition::math::Vector3d LocalAxis (const unsigned int _index) const
 Get the axis of rotation. More...
 
virtual double LowerLimit (unsigned int _index=0) const
 Get the joint's lower limit. More...
 
bool operator== (const Base &_ent) const
 Returns true if the entities are the same. More...
 
ignition::math::Pose3d ParentWorldPose () const
 Get anchor pose on parent link relative to world frame. More...
 
virtual double Position (const unsigned int _index=0) const final
 Get the position of an axis according to its index. More...
 
virtual double PositionImpl (const unsigned int _index) const
 Helper function to get the position of an axis. 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 RemoveChild (physics::BasePtr _child)
 Remove a child by pointer. More...
 
void RemoveChildren ()
 Remove all children. More...
 
virtual void Reset ()
 Reset the joint. More...
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's. More...
 
virtual void SetAnchor (const unsigned int _index, const ignition::math::Vector3d &_anchor)
 Set the anchor point. More...
 
virtual void SetAxis (const unsigned int _index, const ignition::math::Vector3d &_axis)
 Set the axis of rotation where axis is specified in local joint frame. More...
 
virtual void SetDamping (unsigned int _index, double _damping)
 Set the joint damping. More...
 
virtual void SetEffortLimit (unsigned int _index, double _effort)
 Set the effort limit on a joint axis. More...
 
virtual void SetForce (unsigned int _index, double _force)
 Set the force applied to this physics::Joint. More...
 
virtual void SetLowerLimit (const unsigned int _index, const double _limit)
 Set the joint's lower limit. More...
 
void SetModel (ModelPtr _model)
 Set the model this joint belongs too. More...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
virtual bool SetParam (const std::string &_key, unsigned int _index, const boost::any &_value)
 Set a non-generic parameter for the joint. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
virtual bool SetPosition (const unsigned int _index, const double _position, const bool _preserveWorldVelocity=false) override
 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 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 SetState (const JointState &_state)
 Set the joint state. 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...
 
void SetStopDissipation (unsigned int _index, double _dissipation)
 Set joint stop dissipation. More...
 
void SetStopStiffness (unsigned int _index, double _stiffness)
 Set joint stop stiffness. More...
 
virtual void SetUpperLimit (const unsigned int _index, const double _limit)
 Set the joint's upper limit. More...
 
virtual void SetVelocity (unsigned int _index, double _vel)
 Set the velocity of an axis(index). More...
 
virtual void SetVelocityLimit (unsigned int _index, double _velocity)
 Set the velocity limit on a joint axis. More...
 
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to. More...
 
std::string TypeStr () const
 Get the string name for the entity type. More...
 
void Update ()
 Update the joint. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 Update the parameters using new sdf values. More...
 
virtual double UpperLimit (const unsigned int _index=0) const
 Get the joint's upper limit. More...
 
common::URI URI () const
 Return the common::URI of this entity. More...
 
ignition::math::Pose3d WorldPose () const
 Get pose of joint frame relative to world frame. More...
 

Protected Member Functions

ignition::math::Pose3d ChildLinkPose (const unsigned int _index, const double _position)
 internal function to help us compute child link pose if a joint position change is applied. More...
 
void ComputeScopedName ()
 Compute the scoped name of this object based on its parents. More...
 
bool FindAllConnectedLinks (const LinkPtr &_originalParentLink, Link_V &_connectedLinks)
 internal helper to find all links connected to the child link branching out from the children of the child link and any parent of the child link other than the parent link through this joint. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load joint. More...
 
virtual void RegisterIntrospectionItems ()
 Register items in the introspection service. More...
 
virtual void SetForceImpl (unsigned int _index, double _effort)
 Set the force applied to this physics::Joint. More...
 
bool SetPositionMaximal (const unsigned int _index, double _position, const bool _preserveWorldVelocity=false)
 Helper function for maximal coordinate solver SetPosition. More...
 
void SetupJointFeedback ()
 : Setup joint feedback datatructure. More...
 
bool SetVelocityMaximal (unsigned int _index, double _velocity)
 Helper function for maximal coordinate solver SetVelocity. More...
 
virtual void UnregisterIntrospectionItems ()
 Unregister items in the introspection service. More...
 

Protected Attributes

LinkPtr anchorLink
 Anchor link. More...
 
ignition::math::Vector3d anchorPos
 Anchor pose. More...
 
ignition::math::Pose3d 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...
 
btDynamicsWorld * bulletWorld
 Pointer to Bullet's btDynamicsWorld. More...
 
LinkPtr childLink
 The first link this joint connects to. More...
 
Base_V children
 Children of this entity. More...
 
btTypedConstraint * constraint
 Pointer to a contraint object in Bullet. More...
 
double dissipationCoefficient [2]
 joint viscous damping coefficient More...
 
double effortLimit [2]
 Store Joint effort limit as specified in SDF. More...
 
std::vector< common::URIintrospectionItems
 All the introspection items regsitered for this. More...
 
double lowerLimit [2]
 Store Joint position lower limit as specified in SDF. More...
 
ModelPtr model
 Pointer to the parent model. More...
 
BasePtr parent
 Parent of this entity. More...
 
ignition::math::Pose3d 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...
 
sdf::ElementPtr sdf
 The SDF values for this object. More...
 
double springReferencePosition [2]
 joint spring reference (zero load) position More...
 
double stiffnessCoefficient [2]
 joint stiffnessCoefficient More...
 
double upperLimit [2]
 Store Joint position upper limit as specified in SDF. More...
 
double velocityLimit [2]
 Store Joint velocity limit as specified in SDF. More...
 
WorldPtr world
 Pointer to the world. More...
 
JointWrench wrench
 Cache Joint force torque values in case physics engine clears them at the end of update step. More...
 

Detailed Description

A fixed joint.

Member Enumeration Documentation

enum Attribute
inherited

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 

Upper joint limit.

LO_STOP 

Lower joint limit.

enum EntityType
inherited

Unique identifiers for all entity types.

Enumerator
BASE 

Base type.

ENTITY 

Entity type.

MODEL 

Model type.

LINK 

Link type.

COLLISION 

Collision type.

LIGHT 

Light type.

VISUAL 

Visual type.

JOINT 

Joint type.

BALL_JOINT 

BallJoint type.

HINGE2_JOINT 

Hing2Joint type.

HINGE_JOINT 

HingeJoint type.

SLIDER_JOINT 

SliderJoint type.

SCREW_JOINT 

ScrewJoint type.

UNIVERSAL_JOINT 

UniversalJoint type.

GEARBOX_JOINT 

GearboxJoint type.

FIXED_JOINT 

FixedJoint type.

ACTOR 

Actor type.

SHAPE 

Shape type.

BOX_SHAPE 

BoxShape type.

CYLINDER_SHAPE 

CylinderShape type.

HEIGHTMAP_SHAPE 

HeightmapShape type.

MAP_SHAPE 

MapShape type.

MULTIRAY_SHAPE 

MultiRayShape type.

RAY_SHAPE 

RayShape type.

PLANE_SHAPE 

PlaneShape type.

SPHERE_SHAPE 

SphereShape type.

MESH_SHAPE 

MeshShape type.

POLYLINE_SHAPE 

PolylineShape type.

SENSOR_COLLISION 

Indicates a collision shape used for sensing.

Constructor & Destructor Documentation

BulletFixedJoint ( btDynamicsWorld *  world,
BasePtr  _parent 
)

Constructor.

Parameters
[in]worldpointer to the bullet world
[in]_parentpointer to the parent Model
virtual ~BulletFixedJoint ( )
virtual

Destructor.

Member Function Documentation

void AddChild ( BasePtr  _child)
inherited

Add a child to this entity.

Parameters
[in]_childChild entity.
void AddType ( EntityType  _type)
inherited

Add a type specifier.

Parameters
[in]_typeNew type to append to this objects type definition.
virtual ignition::math::Vector3d Anchor ( const unsigned int  _index) const
virtualinherited

Get the anchor point.

Implements Joint.

Reimplemented in BulletScrewJoint, BulletBallJoint, BulletHinge2Joint, BulletUniversalJoint, and BulletHingeJoint.

ignition::math::Pose3d AnchorErrorPose ( ) const
inherited

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

This can be used to compute the bilateral constraint error.

Returns
Pose offset between anchor pose on child and parent, in parent link frame.
virtual void ApplyStiffnessDamping ( )
virtualinherited

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

: rename to ApplySpringStiffnessDamping()

Reimplemented from Joint.

bool AreConnected ( LinkPtr  _one,
LinkPtr  _two 
) const
virtualinherited

Determines of the two bodies are connected by a joint.

Implements Joint.

virtual void Attach ( LinkPtr  _parent,
LinkPtr  _child 
)
virtualinherited

Attach the two bodies with this joint.

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

Reimplemented in ODEJoint, ODEFixedJoint, and DARTJoint.

ignition::math::Quaterniond AxisFrame ( const unsigned int  _index) const
inherited

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

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

Parameters
[in]_indexjoint axis index.
Returns
Orientation of axis frame relative to world frame.
ignition::math::Quaterniond AxisFrameOffset ( const unsigned int  _index) const
inherited

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

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

Parameters
[in]_indexjoint axis index.
Returns
Orientation of axis frame relative to joint frame. If supplied _index is out of range, or use_parent_model_frame is not true, this function returns identity rotation quaternion.
virtual void CacheForceTorque ( )
virtualinherited

Cache Joint Force Torque Values if necessary for physics engine.

Reimplemented from Joint.

double CheckAndTruncateForce ( unsigned int  _index,
double  _effort 
)
inherited

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

Parameters
[in]_indexIndex of the axis.
[in]_effortForce value.
Returns
truncated effort
ignition::math::Pose3d ChildLinkPose ( const unsigned int  _index,
const double  _position 
)
protectedinherited

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

Parameters
[in]_indexaxis index
[in]_positionnew joint position
Returns
new child link pose at new joint position.
void ComputeScopedName ( )
protectedinherited

Compute the scoped name of this object based on its parents.

See Also
Base::GetScopedName
event::ConnectionPtr ConnectJointUpdate ( _subscriber)
inlineinherited

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 EventT< T >::Connect().

virtual void Detach ( )
virtualinherited

Detach this joint from all bodies.

Reimplemented from Joint.

virtual unsigned int DOF ( ) const
inlinevirtualinherited

Implements Joint.

virtual void FillMsg ( msgs::Joint &  _msg)
virtualinherited

Fill a joint message.

Parameters
[out]_msgMessage to fill with this joint's properties.

Reimplemented in GearboxJoint< ODEJoint >, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, and ScrewJoint< BulletJoint >.

Referenced by ScrewJoint< BulletJoint >::FillMsg(), and GearboxJoint< ODEJoint >::FillMsg().

bool FindAllConnectedLinks ( const LinkPtr _originalParentLink,
Link_V _connectedLinks 
)
protectedinherited

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

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

Finialize the object.

Reimplemented from Joint.

BasePtr GetByName ( const std::string &  _name)
inherited

Get by name.

Parameters
[in]_nameGet a child (or self) object by name
Returns
A pointer to the object, NULL if not found
BasePtr GetChild ( unsigned int  _i) const
inherited

Get a child by index.

Parameters
[in]_iIndex of the child to retreive.
Returns
A pointer to the object, NULL if the index is invalid.
BasePtr GetChild ( const std::string &  _name)
inherited

Get a child by name.

Parameters
[in]_nameName of the child.
Returns
A pointer to the object, NULL if not found
LinkPtr GetChild ( ) const
inherited

Get the child link.

Returns
Pointer to the child link.
unsigned int GetChildCount ( ) const
inherited

Get the number of children.

Returns
The number of children.
double GetDamping ( unsigned int  _index)
inherited

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 GetEffortLimit ( unsigned int  _index)
virtualinherited

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 GetForce ( unsigned int  _index)
virtualinherited
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 Joint.

virtual JointWrench GetForceTorque ( unsigned int  _index)
virtualinherited

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

uint32_t GetId ( ) const
inherited

Return the ID of this entity.

This id is unique.

Returns
Integer ID.
double GetInertiaRatio ( const unsigned int  _index) const
inherited

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

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

Parameters
[in]_indexaxis number about which MOI ratio is computed.
Returns
ratio of child MOI to parent MOI.
LinkPtr GetJointLink ( unsigned int  _index) const
virtualinherited

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

Implements Joint.

msgs::Joint::Type GetMsgType ( ) const
inherited

Get the joint type as msgs::Joint::Type.

Returns
Joint type.
std::string GetName ( ) const
inherited

Return the name of the entity.

Returns
Name of the entity.
virtual double GetParam ( const std::string &  _key,
unsigned int  _index 
)
virtualinherited

Get a non-generic parameter for the joint.

See Also
SetParam(const std::string &, unsigned int, const boost::any)
Parameters
[in]_keyString key.
[in]_indexIndex of the axis.

Reimplemented from Joint.

Reimplemented in BulletScrewJoint, BulletUniversalJoint, BulletHingeJoint, and BulletSliderJoint.

LinkPtr GetParent ( ) const
inherited

Get the parent link.

Returns
Pointer to the parent link.
int GetParentId ( ) const
inherited

Return the ID of the parent.

Returns
Integer ID.
bool GetSaveable ( ) const
inherited

Get whether the object should be "saved", when the user selects to save the world to xml.

Returns
True if the object is saveable.
std::string GetScopedName ( bool  _prependWorldName = false) const
inherited

Return the name of this entity with the model scope model1::...::modelN::entityName.

Parameters
[in]_prependWorldNameTrue to prended the returned string with the world name. The result will be world::model1::...::modelN::entityName.
Returns
The scoped name.
virtual const sdf::ElementPtr GetSDF ( )
virtualinherited

Get the SDF values for the object.

Returns
The SDF values for the object.

Reimplemented in Actor, and Model.

double GetSpringReferencePosition ( unsigned int  _index) const
inherited

Get joint spring reference position.

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

Returns the current joint spring stiffness coefficient.

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

Get joint stop dissipation.

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

Get joint stop stiffness.

Parameters
[in]_indexjoint axis index.
Returns
joint stop stiffness coefficient.
unsigned int GetType ( ) const
inherited

Get the full type definition.

Returns
The full type definition.
virtual double 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 Joint.

virtual double GetVelocityLimit ( unsigned int  _index)
virtualinherited

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
const WorldPtr& GetWorld ( ) const
inherited

Get the World this object is in.

Returns
The World this object is part of.
double GetWorldEnergyPotentialSpring ( unsigned int  _index) const
inherited

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

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

Returns
this joint's spring potential energy,
virtual ignition::math::Vector3d GlobalAxis ( const 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 Joint.

bool HasType ( const EntityType _t) const
inherited

Returns true if this object's type definition has the given type.

Parameters
[in]_tType to check.
Returns
True if this object's type definition has the.
double InertiaRatio ( const ignition::math::Vector3d &  _axis) const
inherited

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

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

Parameters
[in]_axisaxis in world frame for which MOI ratio is computed.
Returns
ratio of child MOI to parent MOI.
virtual void Init ( )
virtual

Initialize joint.

Reimplemented from FixedJoint< BulletJoint >.

ignition::math::Pose3d InitialAnchorPose ( ) const
inherited

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

Returns
Joint::anchorPose, initial joint anchor pose.
bool IsSelected ( ) const
inherited

True if the entity is selected by the user.

Returns
True if the entity is selected.
virtual ignition::math::Vector3d LinkForce ( const unsigned int  _index) const
virtualinherited

Get the force the joint applies to the first body.

Parameters
indexThe index of the body(0 or 1)

Implements Joint.

virtual ignition::math::Vector3d LinkTorque ( const unsigned int  _index) const
virtualinherited

Get the torque the joint applies to the first body.

Parameters
indexThe index of the body(0 or 1)

Implements Joint.

virtual void Load ( sdf::ElementPtr  _sdf)
protectedvirtual

Load joint.

Parameters
[in]_sdfPointer to SDF element

Reimplemented from FixedJoint< BulletJoint >.

void Load ( LinkPtr  _parent,
LinkPtr  _child,
const ignition::math::Pose3d &  _pose 
)
inherited

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.
ignition::math::Vector3d LocalAxis ( const unsigned int  _index) const
inherited

Get the axis of rotation.

Parameters
[in]_indexIndex of the axis to get.
Returns
Axis value for the provided index.
virtual double LowerLimit ( unsigned int  _index = 0) const
virtualinherited

Get the joint's lower limit.

For rotational axes, the value is in radians, for prismatic axes it is in meters.

Parameters
[in]_indexIndex of the axis, defaults to 0.
Returns
Lower limit of the axis.

Reimplemented in SimbodyJoint, DARTJoint, BulletBallJoint, BulletHinge2Joint, BulletUniversalJoint, BulletHingeJoint, ODEBallJoint, BulletSliderJoint, SimbodyBallJoint, and SimbodyScrewJoint.

bool operator== ( const Base _ent) const
inherited

Returns true if the entities are the same.

Checks only the name.

Parameters
[in]_entBase object to compare with.
Returns
True if the entities are the same.
ignition::math::Pose3d ParentWorldPose ( ) const
inherited

Get anchor pose on parent link relative to world frame.

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

Returns
Anchor pose on parent link in world frame.
virtual double Position ( const unsigned int  _index = 0) const
finalvirtualinherited

Get the position of an axis according to its index.

For rotational axes, the value is in radians. For prismatic axes, it is in meters.

For static models, it returns the static joint position.

It returns ignition::math::NAN_D in case the position can't be obtained. For instance, if the index is invalid, if the joint is fixed, etc.

Subclasses can't override this method. See PositionImpl instead.

Parameters
[in]_indexIndex of the axis, defaults to 0.
Returns
Current position of the axis.
See Also
PositionImpl
virtual double PositionImpl ( const unsigned int  _index) const
virtual

Helper function to get the position of an axis.

Subclasses must override this.

Parameters
[in]_indexIndex of the axis, defaults to 0.
Returns
Position of the axis.
See Also
Position

Implements Joint.

void Print ( const std::string &  _prefix)
inherited

Print this object to screen via gzmsg.

Parameters
[in]_prefixUsually a set of spaces.
virtual void RegisterIntrospectionItems ( )
protectedvirtualinherited

Register items in the introspection service.

Reimplemented from Base.

virtual void RemoveChild ( unsigned int  _id)
virtualinherited

Remove a child from this entity.

Parameters
[in]_idID of the child to remove.
void RemoveChild ( const std::string &  _name)
inherited

Remove a child by name.

Parameters
[in]_nameName of the child.
void RemoveChild ( physics::BasePtr  _child)
inherited

Remove a child by pointer.

Parameters
[in]_childPointer to the child.
void RemoveChildren ( )
inherited

Remove all children.

virtual void Reset ( )
virtualinherited

Reset the joint.

Reimplemented from Joint.

virtual void Reset ( Base::EntityType  _resetType)
virtualinherited

Calls recursive Reset on one of the Base::EntityType's.

Parameters
[in]_resetTypeThe type of reset operation
virtual void SetAnchor ( const unsigned int  _index,
const ignition::math::Vector3d &  _anchor 
)
virtualinherited

Set the anchor point.

Implements Joint.

Reimplemented in BulletScrewJoint.

virtual void SetAxis ( const unsigned int  _index,
const ignition::math::Vector3d &  _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 Joint.

virtual void SetDamping ( unsigned int  _index,
double  _damping 
)
virtualinherited

Set the joint damping.

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

Implements Joint.

Reimplemented in BulletSliderJoint.

virtual void SetEffortLimit ( unsigned int  _index,
double  _effort 
)
virtualinherited

Set the effort limit on a joint axis.

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

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

virtual void 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 BulletJoint.

virtual void SetLowerLimit ( const unsigned int  _index,
const double  _limit 
)
virtual

Set the joint's lower limit.

For rotational axes, the value is in radians. For prismatic axes, it is in meters.

It returns ignition::math::NAN_D in case the limit can't be obtained. For instance, if the index is invalid, if the joint is fixed, etc.

Parameters
[in]_indexIndex of the axis.
[in]_limitLower limit of the axis.

Reimplemented from Joint.

void SetModel ( ModelPtr  _model)
inherited

Set the model this joint belongs too.

Parameters
[in]_modelPointer to a model.
virtual void SetName ( const std::string &  _name)
virtualinherited

Set the name of the entity.

Parameters
[in]_nameNew name.

Reimplemented in Entity.

virtual bool SetParam ( const std::string &  _key,
unsigned int  _index,
const boost::any &  _value 
)
virtualinherited

Set a non-generic parameter for the joint.

replaces SetAttribute(Attribute, int, double) List of parameters: "friction" Axis Coulomb joint friction coefficient. "hi_stop" Axis upper limit. "lo_stop" Axis lower limit.

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

Implements Joint.

Reimplemented in BulletUniversalJoint, BulletHingeJoint, and BulletSliderJoint.

void SetParent ( BasePtr  _parent)
inherited

Set the parent.

Parameters
[in]_parentParent object.
virtual bool SetPosition ( const unsigned int  _index,
const double  _position,
const bool  _preserveWorldVelocity = false 
)
overridevirtualinherited

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

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

Parameters
[in]_indexIndex of the joint axis (degree of freedom).
[in]_positionPosition to set the joint to. unspecified, pure kinematic teleportation.
[in]_preserveWorldVelocityIf true, the velocity of the child link with respect to the world frame will remain the same after setting the position. By default this is false, which means there are no guarantees about what the child link's world velocity will be after the position is changed (the behavior is determined by the underlying physics engine).
Note
{Only ODE and Bullet support _preserveWorldVelocity being true.}
Returns
returns true if operation succeeds, false if it fails.

Reimplemented from Joint.

bool SetPositionMaximal ( const unsigned int  _index,
double  _position,
const bool  _preserveWorldVelocity = false 
)
protectedinherited

Helper function for maximal coordinate solver SetPosition.

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

Parameters
[in]_indexIndex of the joint axis (degree of freedom).
[in]_positionPosition to set the joint to.
[in]_preserveWorldVelocityTrue if to preserve the world velocity before set position, default is false.
Returns
returns true if operation succeeds, false if it fails.
virtual void SetProvideFeedback ( bool  _enable)
virtualinherited

Set whether the joint should generate feedback.

Parameters
[in]_enableTrue to enable joint feedback.

Reimplemented from Joint.

void SetSaveable ( bool  _v)
inherited

Set whether the object should be "saved", when the user selects to save the world to xml.

Parameters
[in]_vSet to True if the object should be saved.
virtual bool SetSelected ( bool  _show)
virtualinherited

Set whether this entity has been selected by the user through the gui.

Parameters
[in]_showTrue to set this entity as selected.

Reimplemented in Link.

void SetState ( const JointState _state)
inherited

Set the joint state.

Parameters
[in]_stateJoint state
virtual void SetStiffness ( unsigned int  _index,
const double  _stiffness 
)
virtualinherited

Set the joint spring stiffness.

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

Implements Joint.

virtual void SetStiffnessDamping ( unsigned int  _index,
double  _stiffness,
double  _damping,
double  _reference = 0 
)
virtualinherited

Set the joint spring stiffness.

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

Implements Joint.

void SetStopDissipation ( unsigned int  _index,
double  _dissipation 
)
inherited

Set joint stop dissipation.

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

Set joint stop stiffness.

Parameters
[in]_indexjoint axis index.
[in]_stiffnessjoint stop stiffness coefficient.
void SetupJointFeedback ( )
protectedinherited

: Setup joint feedback datatructure.

This is called after Joint::constraint is setup in Init.

virtual void SetUpperLimit ( const unsigned int  _index,
const double  _limit 
)
virtual

Set the joint's upper limit.

For rotational axes, the value is in radians, for prismatic axes it is in meters.

Parameters
[in]_indexIndex of the axis, defaults to 0.
[in]_limitLower limit of the axis.

Reimplemented from Joint.

virtual void SetVelocity ( unsigned int  _index,
double  _vel 
)
virtual

Set the velocity of an axis(index).

In ODE and Bullet, the SetVelocityMaximal function is used to set the velocity of the child link relative to the parent. In Simbody and DART, this function updates the velocity state, which has a recursive effect on the rest of the chain.

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

Implements Joint.

virtual void SetVelocityLimit ( unsigned int  _index,
double  _velocity 
)
virtualinherited

Set the velocity limit on a joint axis.

Parameters
[in]_indexIndex of the axis to set.
[in]_velocityVelocity limit for the axis.
bool SetVelocityMaximal ( unsigned int  _index,
double  _velocity 
)
protectedinherited

Helper function for maximal coordinate solver SetVelocity.

The velocity of the child link of this joint is updated relative to the current parent velocity. It currently does not act recursively.

Parameters
[in]_indexIndex of the joint axis (degree of freedom).
[in]_velocityVelocity to set at this joint.
Returns
returns true if operation succeeds, false if it fails.
void SetWorld ( const WorldPtr _newWorld)
inherited

Set the world this object belongs to.

This will also set the world for all children.

Parameters
[in]_newWorldThe new World this object is part of.
std::string TypeStr ( ) const
inherited

Get the string name for the entity type.

Returns
The string name for this entity.
virtual void UnregisterIntrospectionItems ( )
protectedvirtualinherited

Unregister items in the introspection service.

void Update ( )
virtualinherited

Update the joint.

Reimplemented from Base.

virtual void UpdateParameters ( sdf::ElementPtr  _sdf)
virtualinherited

Update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to update from.

Reimplemented from Base.

virtual double UpperLimit ( const unsigned int  _index = 0) const
virtualinherited

Get the joint's upper limit.

For rotational axes, the value is in radians. For prismatic axes, it is in meters.

It returns ignition::math::NAN_D in case the limit can't be obtained. For instance, if the index is invalid, if the joint is fixed, etc.

Parameters
[in]_indexIndex of the axis, defaults to 0.
Returns
Lower limit of the axis.

Reimplemented in SimbodyJoint, DARTJoint, BulletBallJoint, BulletHinge2Joint, BulletUniversalJoint, BulletHingeJoint, ODEBallJoint, BulletSliderJoint, SimbodyBallJoint, and SimbodyScrewJoint.

common::URI URI ( ) const
inherited

Return the common::URI of this entity.

The URI includes the world where the entity is contained and all the hierarchy of sub-entities that can compose this entity. E.g.: A link entity contains the name of the link and the model where the link is contained.

Returns
The URI of this entity.
ignition::math::Pose3d WorldPose ( ) const
inherited

Get pose of joint frame relative to world frame.

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

Returns
Pose of joint frame relative to world frame.

Member Data Documentation

LinkPtr anchorLink
protectedinherited

Anchor link.

ignition::math::Vector3d anchorPos
protectedinherited

Anchor pose.

This is the xyz position of the joint frame specified in the world frame.

ignition::math::Pose3d anchorPose
protectedinherited

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 applyDamping
protectedinherited

apply damping for adding viscous damping forces on updates

bool axisParentModelFrame[2]
protectedinherited

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

Otherwise use the joint frame. See issue #494.

btDynamicsWorld* bulletWorld
protectedinherited

Pointer to Bullet's btDynamicsWorld.

LinkPtr childLink
protectedinherited

The first link this joint connects to.

Base_V children
protectedinherited

Children of this entity.

btTypedConstraint* constraint
protectedinherited

Pointer to a contraint object in Bullet.

double dissipationCoefficient[2]
protectedinherited

joint viscous damping coefficient

double effortLimit[2]
protectedinherited

Store Joint effort limit as specified in SDF.

std::vector<common::URI> introspectionItems
protectedinherited

All the introspection items regsitered for this.

double lowerLimit[2]
protectedinherited

Store Joint position lower limit as specified in SDF.

ModelPtr model
protectedinherited

Pointer to the parent model.

BasePtr parent
protectedinherited

Parent of this entity.

ignition::math::Pose3d parentAnchorPose
protectedinherited

Anchor pose relative to parent link frame.

LinkPtr parentLink
protectedinherited

The second link this joint connects to.

bool provideFeedback
protectedinherited

Provide Feedback data for contact forces.

sdf::ElementPtr sdf
protectedinherited

The SDF values for this object.

double springReferencePosition[2]
protectedinherited

joint spring reference (zero load) position

double stiffnessCoefficient[2]
protectedinherited

joint stiffnessCoefficient

double upperLimit[2]
protectedinherited

Store Joint position upper limit as specified in SDF.

double velocityLimit[2]
protectedinherited

Store Joint velocity limit as specified in SDF.

WorldPtr world
protectedinherited

Pointer to the world.

JointWrench wrench
protectedinherited

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


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