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

An ODEBallJoint. More...

#include <ODEBallJoint.hh>

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

Public Member Functions

 ODEBallJoint (dWorldID worldId, BasePtr _parent)
 Constructor.
 
virtual ~ODEBallJoint ()
 Destructor.
 
virtual math::Vector3 GetAnchor (int index) const
 Get joint's anchor point.
 
virtual math::Angle GetAngleImpl (int) const
 Get the angle of rotation of an axis(index)
 
virtual math::Vector3 GetGlobalAxis (int) const
 Get the axis of rotation.
 
virtual double GetMaxForce (int)
 Get the max allowed force of an axis(index).
 
virtual double GetVelocity (int) const
 Get the rotation rate of an axis(index)
 
virtual void SetAnchor (int index, const math::Vector3 &anchor)
 Set joint's anchor point.
 
virtual void SetDamping (int _index, double _damping)
 Set joint damping, not yet implemented.
 
virtual void SetMaxForce (int, double)
 Set the max allowed force of an axis(index).
 
virtual void SetVelocity (int, double)
 Set the velocity of an axis(index).
 
- Public Member Functions inherited from gazebo::physics::BallJoint< ODEJoint >
 BallJoint (BasePtr _parent)
 Constructor.
 
virtual ~BallJoint ()
 Destructor.
 
virtual math::Angle GetHighStop (int)
 Get the high stop of an axis(index).
 
virtual math::Angle GetLowStop (int)
 Get the low stop of an axis(index).
 
virtual void SetAxis (int, const math::Vector3 &)
 Set the axis of rotation.
 
virtual void SetHighStop (int, math::Angle)
 
virtual void SetLowStop (int, math::Angle)
 
- Public Member Functions inherited from gazebo::physics::ODEJoint
 ODEJoint (BasePtr _parent)
 Constructor.
 
virtual ~ODEJoint ()
 Destructor.
 
virtual bool AreConnected (LinkPtr _one, LinkPtr _two) const
 Determines of the two bodies are connected by a joint.
 
virtual void Attach (LinkPtr parent, LinkPtr child)
 Attach the two bodies with this joint.
 
virtual void Detach ()
 Detach this joint from all bodies.
 
double GetCFM ()
 Get the ERP of this joint.
 
double GetERP ()
 Get the ERP of this joint.
 
dJointFeedback * GetFeedback ()
 Get the feedback data structure for this joint, if set.
 
virtual LinkPtr GetJointLink (int _index) const
 Get the link to which the joint is attached according the _index.
 
virtual math::Vector3 GetLinkForce (unsigned int index) const
 Get the force the joint applies to the first link.
 
virtual math::Vector3 GetLinkTorque (unsigned int index) const
 Get the torque the joint applies to the first link.
 
virtual double GetParam (int _parameter) const
 The default function does nothing.
 
virtual void Reset ()
 Reset the joint.
 
virtual void SetAttribute (Attribute, int index, double value)
 Set a parameter for the joint.
 
void SetCFM (double newCFM)
 Set the CFM of this joint.
 
void SetERP (double newERP)
 Set the ERP of this 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 SetParam (int _parameter, double _value)
 By default this does nothing.
 
- Public Member Functions inherited from gazebo::physics::Joint
 Joint (BasePtr _parent)
 Constructor.
 
virtual ~Joint ()
 Destructor.
 
template<typename T >
event::ConnectionPtr ConnectJointUpdate (T _subscriber)
 Connect a boost::slot the the joint update signal.
 
void DisconnectJointUpdate (event::ConnectionPtr &_conn)
 Disconnect a boost::slot the the joint update signal.
 
void FillJointMsg (msgs::Joint &_msg) GAZEBO_DEPRECATED
 DEPRECATED.
 
void FillMsg (msgs::Joint &_msg)
 Fill a joint message.
 
math::Angle GetAngle (int _index) const
 Get the angle of rotation of an axis(index)
 
LinkPtr GetChild () const
 Get the child link.
 
virtual double GetForce (int _index)
 
math::Vector3 GetLocalAxis (int _index) const
 Get the axis of rotation.
 
LinkPtr GetParent () const
 Get the parent link.
 
JointState GetState ()
 Get the joint state.
 
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 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 SetForce (int _index, double _force)
 Set the force applied to this physics::Joint.
 
void SetModel (ModelPtr _model)
 Set the model this joint belongs too.
 
void SetState (const JointState &_state)
 Set the joint state.
 
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
 Get a child or self by id.
 
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 WorldPtrGetWorld () const
 Get the World this object is in.
 
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type.
 
bool IsSelected () const
 True if the entity is selected by the user.
 
bool operator== (const Base &_ent) const
 Returns true if the entities are the same.
 
void Print (const std::string &_prefix)
 Print this object to screen via gzmsg.
 
virtual void RemoveChild (unsigned int _id)
 Remove a child from this entity.
 
void RemoveChild (const std::string &_name)
 Remove a child by name.
 
void RemoveChildren ()
 Remove all children.
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's.
 
virtual void SetName (const std::string &_name)
 Set the name of the entity.
 
void SetParent (BasePtr _parent)
 Set the parent.
 
void SetSaveable (bool _v)
 Set whether the object should be "saved", when the user selects to save the world to xml.
 
virtual bool SetSelected (bool _show)
 Set whether this entity has been selected by the user through the gui.
 
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to.
 

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...
 
- Protected Member Functions inherited from gazebo::physics::BallJoint< ODEJoint >
void Load (sdf::ElementPtr _sdf)
 Template to ::Load the BallJoint.
 
- Protected Attributes inherited from gazebo::physics::ODEJoint
dJointID jointId
 This is our id.
 

Detailed Description

An ODEBallJoint.

Constructor & Destructor Documentation

gazebo::physics::ODEBallJoint::ODEBallJoint ( dWorldID  worldId,
BasePtr  _parent 
)

Constructor.

virtual gazebo::physics::ODEBallJoint::~ODEBallJoint ( )
virtual

Destructor.

Member Function Documentation

virtual math::Vector3 gazebo::physics::ODEBallJoint::GetAnchor ( int  index) const
virtual

Get joint's anchor point.

Implements gazebo::physics::Joint.

virtual math::Angle gazebo::physics::ODEBallJoint::GetAngleImpl ( int  ) const
inlinevirtual

Get the angle of rotation of an axis(index)

Implements gazebo::physics::Joint.

virtual math::Vector3 gazebo::physics::ODEBallJoint::GetGlobalAxis ( int  ) const
inlinevirtual

Get the axis of rotation.

Implements gazebo::physics::Joint.

virtual double gazebo::physics::ODEBallJoint::GetMaxForce ( int  )
inlinevirtual

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

Implements gazebo::physics::Joint.

virtual double gazebo::physics::ODEBallJoint::GetVelocity ( int  ) const
inlinevirtual

Get the rotation rate of an axis(index)

Implements gazebo::physics::Joint.

virtual void gazebo::physics::ODEBallJoint::SetAnchor ( int  index,
const math::Vector3 anchor 
)
virtual

Set joint's anchor point.

Implements gazebo::physics::Joint.

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

Set joint damping, not yet implemented.

Implements gazebo::physics::Joint.

virtual void gazebo::physics::ODEBallJoint::SetMaxForce ( int  ,
double   
)
inlinevirtual

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

Implements gazebo::physics::Joint.

virtual void gazebo::physics::ODEBallJoint::SetVelocity ( int  ,
double   
)
inlinevirtual

Set the velocity of an axis(index).

Implements gazebo::physics::Joint.


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