Link Class Referenceabstract

Link class defines a rigid body entity, containing information on inertia, visual and collision properties of a rigid body. More...

#include <physics/physics.hh>

Inherits Entity.

Inherited by BulletLink, DARTLink, ODELink, and SimbodyLink.

Public Types

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

 Link (EntityPtr _parent)
 Constructor. More...
 
virtual ~Link ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
void AddChildJoint (JointPtr _joint)
 Joints that have this Link as a parent Link. More...
 
virtual void AddForce (const ignition::math::Vector3d &_force)=0
 Add a force to the body. More...
 
virtual void AddForceAtRelativePosition (const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_relPos)=0
 Add a force (in world frame coordinates) to the body at a position relative to the center of mass which is expressed in the link's own frame of reference. More...
 
virtual void AddForceAtWorldPosition (const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_pos)=0
 Add a force to the body using a global position. More...
 
virtual void AddLinkForce (const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_offset=ignition::math::Vector3d::Zero)=0
 Add a force expressed in the link frame. More...
 
void AddParentJoint (JointPtr _joint)
 Joints that have this Link as a child Link. More...
 
virtual void AddRelativeForce (const ignition::math::Vector3d &_force)=0
 Add a force to the body, components are relative to the body's own frame of reference. More...
 
virtual void AddRelativeTorque (const ignition::math::Vector3d &_torque)=0
 Add a torque to the body, components are relative to the body's own frame of reference. More...
 
virtual void AddTorque (const ignition::math::Vector3d &_torque)=0
 Add a torque to the body. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
void AttachStaticModel (ModelPtr &_model, const ignition::math::Pose3d &_offset)
 Attach a static model to this link. More...
 
common::BatteryPtr Battery (const std::string &_name) const
 Get a battery by name. More...
 
common::BatteryPtr Battery (const size_t _index) const
 Get a battery based on an index. More...
 
size_t BatteryCount () const
 Get the number of batteries in this link. More...
 
virtual ignition::math::Box BoundingBox () const
 Get the bounding box for the link and all the child elements. More...
 
ignition::math::Box CollisionBoundingBox () const
 Returns collision bounding box. More...
 
event::ConnectionPtr ConnectEnabled (std::function< void(bool)> _subscriber)
 Connect to the add entity signal. More...
 
void DetachAllStaticModels ()
 Detach all static models from this link. More...
 
void DetachStaticModel (const std::string &_modelName)
 Detach a static model from this link. More...
 
const ignition::math::Pose3d & DirtyPose () const
 Returns Entity::dirtyPose. More...
 
void FillMsg (msgs::Link &_msg)
 Fill a link message. More...
 
bool FindAllConnectedLinksHelper (const LinkPtr &_originalParentLink, Link_V &_connectedLinks, bool _fistLink=false)
 Helper function to find all connected links of a link based on parent/child relations of joints. More...
 
void Fini ()
 Finalize the body. More...
 
double GetAngularDamping () const
 Get the angular damping factor. 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...
 
CollisionPtr GetChildCollision (const std::string &_name)
 Get a child collision entity, if one exists. More...
 
unsigned int GetChildCount () const
 Get the number of children. More...
 
Joint_V GetChildJoints () const
 Get the child joints. More...
 
Link_V GetChildJointsLinks () const
 Returns a vector of children Links connected by joints. More...
 
LinkPtr GetChildLink (const std::string &_name)
 Get a child linke entity, if one exists. More...
 
CollisionPtr GetCollision (const std::string &_name)
 Get a child collision by name. More...
 
CollisionPtr GetCollision (unsigned int _index) const
 Get a child collision by index. More...
 
Collision_V GetCollisions () const
 Get all the child collisions. More...
 
virtual bool GetEnabled () const =0
 Get whether this body is enabled in the physics engine. More...
 
virtual bool GetGravityMode () const =0
 Get the gravity mode. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
InertialPtr GetInertial () const
 Get the inertia of the link. More...
 
virtual bool GetKinematic () const
 Implement this function. More...
 
double GetLinearDamping () const
 Get the linear damping factor. More...
 
ModelPtr GetModel () const
 Get the model that this body belongs to. More...
 
std::string GetName () const
 Return the name of the entity. More...
 
void GetNearestEntityBelow (double &_distBelow, std::string &_entityName)
 Get the distance to the nearest entity below (along the Z-axis) this entity. More...
 
BasePtr GetParent () const
 Get the parent. More...
 
int GetParentId () const
 Return the ID of the parent. More...
 
Joint_V GetParentJoints () const
 Get the parent joints. More...
 
Link_V GetParentJointsLinks () const
 Returns a vector of parent Links connected by joints. More...
 
ModelPtr GetParentModel ()
 Get the parent model, if one exists. 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...
 
bool GetSelfCollide () const
 Get Self-Collision Flag. More...
 
unsigned int GetSensorCount () const
 Get sensor count. More...
 
std::string GetSensorName (unsigned int _index) const
 Get sensor name. More...
 
unsigned int GetType () const
 Get the full type definition. More...
 
msgs::Visual GetVisualMessage (const std::string &_name) const
 Returns the visual message specified by its name. More...
 
const WorldPtrGetWorld () const
 Get the World this object is in. More...
 
double GetWorldEnergy () const
 Returns this link's total energy, or sum of Link::GetWorldEnergyPotential() and Link::GetWorldEnergyKinetic(). More...
 
double GetWorldEnergyKinetic () const
 Returns this link's kinetic energy computed using link's CoG velocity in the inertial (world) frame. More...
 
double GetWorldEnergyPotential () const
 Returns this link's potential energy, based on position in world frame and gravity. More...
 
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type. More...
 
virtual void Init ()
 Initialize the body. More...
 
ignition::math::Pose3d InitialRelativePose () const
 Get the initial relative pose. More...
 
bool IsCanonicalLink () const
 A helper function that checks if this is a canonical body. More...
 
bool IsSelected () const
 True if the entity is selected by the user. More...
 
bool IsStatic () const
 Return whether this entity is static. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load the body based on an SDF element. More...
 
void MoveFrame (const ignition::math::Pose3d &_worldReferenceFrameSrc, const ignition::math::Pose3d &_worldReferenceFrameDst, const bool _preserveWorldVelocity=false)
 Move Link given source and target frames specified in world coordinates. More...
 
virtual void OnPoseChange ()
 This function is called when the entity's (or one of its parents) pose of the parent has changed. More...
 
bool operator== (const Base &_ent) const
 Returns true if the entities are the same. More...
 
void PlaceOnEntity (const std::string &_entityName)
 Move this entity to be ontop of another entity by name. More...
 
void PlaceOnNearestEntityBelow ()
 Move this entity to be ontop of the nearest entity below. More...
 
void Print (const std::string &_prefix)
 Print this object to screen via gzmsg. More...
 
void ProcessMsg (const msgs::Link &_msg)
 Update parameters from a message. More...
 
ignition::math::Vector3d RelativeAngularAccel () const
 Get the angular acceleration of the body. More...
 
ignition::math::Vector3d RelativeAngularVel () const
 Get the angular velocity of the body. More...
 
ignition::math::Vector3d RelativeForce () const
 Get the force applied to the body. More...
 
ignition::math::Vector3d RelativeLinearAccel () const
 Get the linear acceleration of the body. More...
 
ignition::math::Vector3d RelativeLinearVel () const
 Get the linear velocity of the body. More...
 
ignition::math::Pose3d RelativePose () const
 Get the pose of the entity relative to its parent. More...
 
ignition::math::Vector3d RelativeTorque () const
 Get the torque applied to the body. More...
 
const ignition::math::Vector3d RelativeWindLinearVel () const
 Returns this link's wind velocity. 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...
 
virtual void RemoveChild (EntityPtr _child)
 
void RemoveChildJoint (const std::string &_jointName)
 Remove Joints that have this Link as a parent Link. More...
 
void RemoveChildren ()
 Remove all children. More...
 
void RemoveCollision (const std::string &_name)
 Remove a collision from the link. More...
 
void RemoveParentJoint (const std::string &_jointName)
 Remove Joints that have this Link as a child Link. More...
 
void Reset ()
 Reset the link. More...
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's. More...
 
void ResetPhysicsStates ()
 Reset the velocity, acceleration, force and torque of link. More...
 
void SetAngularAccel (const ignition::math::Vector3d &_accel) GAZEBO_DEPRECATED(9.0)
 Set the angular acceleration of the body. More...
 
virtual void SetAngularDamping (double _damping)=0
 Set the angular damping factor. More...
 
virtual void SetAngularVel (const ignition::math::Vector3d &_vel)=0
 Set the angular velocity of the body. More...
 
void SetAnimation (const common::PoseAnimationPtr &_anim, boost::function< void()> _onComplete)
 Set an animation for this entity. More...
 
void SetAnimation (common::PoseAnimationPtr _anim)
 Set an animation for this entity. More...
 
virtual void SetAutoDisable (bool _disable)=0
 Allow the link to auto disable. More...
 
void SetCanonicalLink (bool _value)
 Set to true if this entity is a canonical link for a model. More...
 
void SetCollideMode (const std::string &_mode)
 Set the collide mode of the body. More...
 
virtual void SetEnabled (bool _enable) const =0
 Set whether this body is enabled. More...
 
virtual void SetForce (const ignition::math::Vector3d &_force)=0
 Set the force applied to the body. More...
 
virtual void SetGravityMode (bool _mode)=0
 Set whether gravity affects this body. More...
 
void SetInertial (const InertialPtr &_inertial)
 Set the mass of the link. More...
 
void SetInitialRelativePose (const ignition::math::Pose3d &_pose)
 Set the initial pose. More...
 
virtual void SetKinematic (const bool &_kinematic)
 Implement this function. More...
 
void SetLaserRetro (float _retro)
 Set the laser retro reflectiveness. More...
 
void SetLinearAccel (const ignition::math::Vector3d &_accel) GAZEBO_DEPRECATED(9.0)
 Set the linear acceleration of the body. More...
 
virtual void SetLinearDamping (double _damping)=0
 Set the linear damping factor. More...
 
virtual void SetLinearVel (const ignition::math::Vector3d &_vel)=0
 Set the linear velocity of the body. More...
 
virtual void SetLinkStatic (bool _static)=0
 Freeze link to ground (inertial frame). More...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
void SetPublishData (bool _enable)
 Enable/Disable link data publishing. More...
 
void SetRelativePose (const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true)
 Set the pose of the entity relative to its parent. More...
 
void SetSaveable (bool _v)
 Set whether the object should be "saved", when the user selects to save the world to xml. More...
 
void SetScale (const ignition::math::Vector3d &_scale)
 Set the scale of the link. More...
 
virtual bool SetSelected (bool _set)
 Set whether this entity has been selected by the user through the gui. More...
 
virtual void SetSelfCollide (bool _collide)=0
 Set whether this body will collide with others in the model. More...
 
void SetState (const LinkState &_state)
 Set the current link state. More...
 
virtual void SetStatic (const bool &_static)
 
virtual void SetTorque (const ignition::math::Vector3d &_torque)=0
 Set the torque applied to the body. More...
 
bool SetVisualPose (const uint32_t _id, const ignition::math::Pose3d &_pose)
 Set the pose of a visual. More...
 
void SetWindEnabled (const bool _enable)
 Enable/disable wind for this link. More...
 
virtual void SetWindMode (const bool _mode)
 Set whether wind affects this body. More...
 
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to. More...
 
void SetWorldPose (const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true)
 Set the world pose of the entity. More...
 
void SetWorldTwist (const ignition::math::Vector3d &_linear, const ignition::math::Vector3d &_angular, const bool _updateChildren=true)
 Set angular and linear rates of an physics::Entity. More...
 
virtual void StopAnimation ()
 Stop the current animation, if any. More...
 
std::string TypeStr () const
 Get the string name for the entity type. More...
 
void Update (const common::UpdateInfo &_info)
 Update the collision. More...
 
virtual void Update ()
 Update the object. More...
 
virtual void UpdateMass ()
 Update the mass matrix. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 Update the parameters using new sdf values. More...
 
virtual void UpdateSurface ()
 Update surface parameters. More...
 
void UpdateWind (const common::UpdateInfo &_info)
 Update the wind. More...
 
common::URI URI () const
 Return the common::URI of this entity. More...
 
bool VisualId (const std::string &_visName, uint32_t &_visualId) const
 Get the unique ID of a visual. More...
 
bool VisualPose (const uint32_t _id, ignition::math::Pose3d &_pose) const
 Get the pose of a visual. More...
 
virtual bool WindMode () const
 Get the wind mode. More...
 
ignition::math::Vector3d WorldAngularAccel () const
 Get the angular acceleration of the body in the world frame, which is computed as (I^-1 * (T - w x L)), where I: inertia matrix in world frame T: sum of external torques in world frame L: angular momentum of CoG in world frame w: angular velocity in world frame. More...
 
ignition::math::Vector3d WorldAngularMomentum () const
 Get the angular momentum of the body CoG in the world frame, which is computed as (I * w), where I: inertia matrix in world frame w: angular velocity in world frame. More...
 
virtual ignition::math::Vector3d WorldAngularVel () const
 Get the angular velocity of the entity in the world frame. More...
 
virtual ignition::math::Vector3d WorldCoGLinearVel () const =0
 Get the linear velocity at the body's center of gravity in the world frame. More...
 
ignition::math::Pose3d WorldCoGPose () const
 Get the pose of the body's center of gravity in the world coordinate frame. More...
 
virtual ignition::math::Vector3d WorldForce () const =0
 Get the force applied to the body in the world frame. More...
 
ignition::math::Pose3d WorldInertialPose () const
 Get the world pose of the link inertia (cog position and Moment of Inertia frame). More...
 
ignition::math::Matrix3d WorldInertiaMatrix () const
 Get the inertia matrix in the world frame. More...
 
ignition::math::Vector3d WorldLinearAccel () const
 Get the linear acceleration of the body in the world frame. More...
 
virtual ignition::math::Vector3d WorldLinearVel () const
 Get the linear velocity of the origin of the link frame, expressed in the world frame. More...
 
virtual ignition::math::Vector3d WorldLinearVel (const ignition::math::Vector3d &_offset) const =0
 Get the linear velocity of a point on the body in the world frame, using an offset expressed in a body-fixed frame. More...
 
virtual ignition::math::Vector3d WorldLinearVel (const ignition::math::Vector3d &_offset, const ignition::math::Quaterniond &_q) const =0
 Get the linear velocity of a point on the body in the world frame, using an offset expressed in an arbitrary frame. More...
 
virtual const
ignition::math::Pose3d & 
WorldPose () const
 Get the absolute pose of the entity. More...
 
virtual ignition::math::Vector3d WorldTorque () const =0
 Get the torque applied to the body about the center of mass in world frame coordinates. More...
 
const ignition::math::Vector3d WorldWindLinearVel () const
 Returns this link's wind velocity in the world coordinate frame. More...
 

Protected Types

typedef std::map< uint32_t,
msgs::Visual > 
Visuals_M
 

Protected Member Functions

void ComputeScopedName ()
 Compute the scoped name of this object based on its parents. More...
 
virtual void RegisterIntrospectionItems ()
 Register items in the introspection service. More...
 
virtual void UnregisterIntrospectionItems ()
 Unregister items in the introspection service. More...
 

Protected Attributes

ignition::math::Vector3d angularAccel
 Angular acceleration. More...
 
common::PoseAnimationPtr animation
 Current pose animation. More...
 
event::ConnectionPtr animationConnection
 Connection used to update an animation. More...
 
ignition::math::Pose3d animationStartPose
 Start pose of an animation. More...
 
std::vector
< ignition::math::Pose3d > 
attachedModelsOffset
 Offsets for the attached models. More...
 
Base_V children
 Children of this entity. More...
 
std::vector< event::ConnectionPtrconnections
 All our event connections. More...
 
ignition::math::Pose3d dirtyPose
 The pose set by a physics engine. More...
 
InertialPtr inertial
 Inertial properties. More...
 
bool initialized = false
 This flag is set to true when the link is initialized. More...
 
std::vector< common::URIintrospectionItems
 All the introspection items regsitered for this. More...
 
ignition::math::Vector3d linearAccel
 Linear acceleration. More...
 
transport::NodePtr node
 Communication node. More...
 
ignition::transport::Node nodeIgn
 Ignition communication node. More...
 
BasePtr parent
 Parent of this entity. More...
 
EntityPtr parentEntity
 A helper that prevents numerous dynamic_casts. More...
 
common::Time prevAnimationTime
 Previous time an animation was updated. More...
 
transport::PublisherPtr requestPub
 Request publisher. More...
 
ignition::transport::Node::Publisher requestPubIgn
 Request publisher. More...
 
ignition::math::Vector3d scale
 Scale of the entity. More...
 
sdf::ElementPtr sdf
 The SDF values for this object. More...
 
transport::PublisherPtr visPub
 Visual publisher. More...
 
ignition::transport::Node::Publisher visPubIgn
 Visual publisher. More...
 
msgs::Visual * visualMsg
 Visual message container. More...
 
Visuals_M visuals
 Link visual elements. More...
 
WorldPtr world
 Pointer to the world. More...
 
ignition::math::Pose3d worldPose
 World pose of the entity. More...
 

Detailed Description

Link class defines a rigid body entity, containing information on inertia, visual and collision properties of a rigid body.

Member Typedef Documentation

typedef std::map<uint32_t, msgs::Visual> Visuals_M
protected

Member Enumeration Documentation

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

Link ( EntityPtr  _parent)
explicit

Constructor.

Parameters
[in]_parentParent of this link.
virtual ~Link ( )
virtual

Destructor.

Member Function Documentation

void AddChild ( BasePtr  _child)
inherited

Add a child to this entity.

Parameters
[in]_childChild entity.
void AddChildJoint ( JointPtr  _joint)

Joints that have this Link as a parent Link.

Parameters
[in]_jointJoint that is a child of this link.
virtual void AddForce ( const ignition::math::Vector3d &  _force)
pure virtual

Add a force to the body.

Parameters
[in]_forceForce to add.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

virtual void AddForceAtRelativePosition ( const ignition::math::Vector3d &  _force,
const ignition::math::Vector3d &  _relPos 
)
pure virtual

Add a force (in world frame coordinates) to the body at a position relative to the center of mass which is expressed in the link's own frame of reference.

Parameters
[in]_forceForce to add. The force must be expressed in the world reference frame.
[in]_relPosPosition on the link to add the force. This position must be expressed in the link's coordinates with respect to the link's center of mass.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

virtual void AddForceAtWorldPosition ( const ignition::math::Vector3d &  _force,
const ignition::math::Vector3d &  _pos 
)
pure virtual

Add a force to the body using a global position.

Parameters
[in]_forceForce to add.
[in]_posPosition in global coord frame to add the force.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

virtual void AddLinkForce ( const ignition::math::Vector3d &  _force,
const ignition::math::Vector3d &  _offset = ignition::math::Vector3d::Zero 
)
pure virtual

Add a force expressed in the link frame.

Parameters
[in]_forceForce to add. The force must be expressed in the link-fixed reference frame.
[in]_offsetOffset position expressed in coordinates of the link frame with respect to the link frame's origin. It defaults to the link origin.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

void AddParentJoint ( JointPtr  _joint)

Joints that have this Link as a child Link.

Parameters
[in]_jointJoint that is a parent of this link.
virtual void AddRelativeForce ( const ignition::math::Vector3d &  _force)
pure virtual

Add a force to the body, components are relative to the body's own frame of reference.

Parameters
[in]_forceForce to add.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

virtual void AddRelativeTorque ( const ignition::math::Vector3d &  _torque)
pure virtual

Add a torque to the body, components are relative to the body's own frame of reference.

Parameters
[in]_torqueTorque value to add.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

virtual void AddTorque ( const ignition::math::Vector3d &  _torque)
pure virtual

Add a torque to the body.

Parameters
[in]_torqueTorque value to add to the link.

Implemented in BulletLink, SimbodyLink, ODELink, and DARTLink.

void AddType ( EntityType  _type)
inherited

Add a type specifier.

Parameters
[in]_typeNew type to append to this objects type definition.
void AttachStaticModel ( ModelPtr _model,
const ignition::math::Pose3d &  _offset 
)

Attach a static model to this link.

Parameters
[in]_modelPointer to a static model.
[in]_offsetPose relative to this link to place the model.
common::BatteryPtr Battery ( const std::string &  _name) const

Get a battery by name.

Parameters
[in]_nameName of the battery to get.
Returns
Pointer to the battery, NULL if the name is invalid.
common::BatteryPtr Battery ( const size_t  _index) const

Get a battery based on an index.

Returns
A pointer to a Battery. Null if the _index is invalid.
size_t BatteryCount ( ) const

Get the number of batteries in this link.

Returns
Size of this->batteries array.
See Also
Link::Battery()
virtual ignition::math::Box BoundingBox ( ) const
virtual

Get the bounding box for the link and all the child elements.

Returns
The link's bounding box.

Reimplemented from Entity.

ignition::math::Box CollisionBoundingBox ( ) const
inherited

Returns collision bounding box.

Returns
Collsion bounding box.
void ComputeScopedName ( )
protectedinherited

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

See Also
Base::GetScopedName
event::ConnectionPtr ConnectEnabled ( std::function< void(bool)>  _subscriber)

Connect to the add entity signal.

Parameters
[in]_subscriberSubsciber callback function.
Returns
Pointer to the connection, which must be kept in scope.
void DetachAllStaticModels ( )

Detach all static models from this link.

void DetachStaticModel ( const std::string &  _modelName)

Detach a static model from this link.

Parameters
[in]_modelNameName of an attached model to detach.
const ignition::math::Pose3d& DirtyPose ( ) const
inherited

Returns Entity::dirtyPose.

The dirty pose is the pose set by the physics engine before it's value is propagated to the rest of the simulator.

Returns
The dirty pose of the entity.
void FillMsg ( msgs::Link &  _msg)

Fill a link message.

Parameters
[out]_msgMessage to fill
bool FindAllConnectedLinksHelper ( const LinkPtr _originalParentLink,
Link_V _connectedLinks,
bool  _fistLink = false 
)

Helper function to find all connected links of a link based on parent/child relations of joints.

For example, if Link0 –> Link1 –> ... –> LinkN is a kinematic chain with Link0 being the base link. Then, call by Link1: Link1->FindAllConnectedLinksHelper(Link0, _list, true); should return true with _list containing Link1 through LinkN. In the case the _originalParentLink is part of a loop, _connectedLinks is cleared and the function returns false.

Parameters
[in]_originParentLinkif this link is a child link of the search, we've found a loop.
in/out]_connectedLinks aggregate list of connected links.
[in]_fistLinkthis is the first Link, skip over the parent link that matches the _originalParentLink.
Returns
true if successfully found a subset of connected links
void Fini ( )
virtual

Finalize the body.

Reimplemented from Entity.

Reimplemented in SimbodyLink, and ODELink.

double GetAngularDamping ( ) const

Get the angular damping factor.

Returns
Angular damping.
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
CollisionPtr GetChildCollision ( const std::string &  _name)
inherited

Get a child collision entity, if one exists.

Parameters
[in]_nameName of the child collision object.
Returns
Pointer to the Collision object, or NULL if not found.
unsigned int GetChildCount ( ) const
inherited

Get the number of children.

Returns
The number of children.
Joint_V GetChildJoints ( ) const

Get the child joints.

Link_V GetChildJointsLinks ( ) const

Returns a vector of children Links connected by joints.

Returns
A vector of children Links connected by joints.
LinkPtr GetChildLink ( const std::string &  _name)
inherited

Get a child linke entity, if one exists.

Parameters
[in]_nameName of the child Link object.
Returns
Pointer to the Link object, or NULL if not found.
CollisionPtr GetCollision ( const std::string &  _name)

Get a child collision by name.

Parameters
[in]_nameName of the collision object.
Returns
Pointer to the collision, NULL if the name was not found.
CollisionPtr GetCollision ( unsigned int  _index) const

Get a child collision by index.

Parameters
[in]_indexIndex of the collision object.
Returns
Pointer to the collision, NULL if the name was not found.
Collision_V GetCollisions ( ) const

Get all the child collisions.

Returns
A std::vector of all the child collisions.
virtual bool GetEnabled ( ) const
pure virtual

Get whether this body is enabled in the physics engine.

Returns
True if the link is enabled.

Implemented in DARTLink, SimbodyLink, BulletLink, and ODELink.

virtual bool GetGravityMode ( ) const
pure virtual

Get the gravity mode.

Returns
True if gravity is enabled.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

uint32_t GetId ( ) const
inherited

Return the ID of this entity.

This id is unique.

Returns
Integer ID.
InertialPtr GetInertial ( ) const
inline

Get the inertia of the link.

Returns
Inertia of the link.

References Link::inertial.

virtual bool GetKinematic ( ) const
inlinevirtual

Implement this function.

Get whether this body is in the kinematic state.

Returns
True if the link is kinematic only.

Reimplemented in ODELink, and DARTLink.

double GetLinearDamping ( ) const

Get the linear damping factor.

Returns
Linear damping.
ModelPtr GetModel ( ) const

Get the model that this body belongs to.

Returns
Model that this body belongs to.
std::string GetName ( ) const
inherited

Return the name of the entity.

Returns
Name of the entity.
void GetNearestEntityBelow ( double &  _distBelow,
std::string &  _entityName 
)
inherited

Get the distance to the nearest entity below (along the Z-axis) this entity.

Parameters
[out]_distBelowThe distance to the nearest entity below.
[out]_entityNameThe name of the nearest entity below.
BasePtr GetParent ( ) const
inherited

Get the parent.

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

Return the ID of the parent.

Returns
Integer ID.
Joint_V GetParentJoints ( ) const

Get the parent joints.

Link_V GetParentJointsLinks ( ) const

Returns a vector of parent Links connected by joints.

Returns
Vector of parent Links connected by joints.
ModelPtr GetParentModel ( )
inherited

Get the parent model, if one exists.

Returns
Pointer to a model, or NULL if no parent model exists.
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.

bool GetSelfCollide ( ) const

Get Self-Collision Flag.

Two links within the same model will not collide if both have self_collide == false.
link 1 and link2 collide = link1.self_collide || link2.self_collide Bodies connected by a joint are exempt from this, and will never collide.

Returns
True if self collision is enabled.
unsigned int GetSensorCount ( ) const

Get sensor count.

This will return the number of sensors created by the link when it was loaded. This function is commonly used with Link::GetSensorName.

Returns
The number of sensors created by the link.
std::string GetSensorName ( unsigned int  _index) const

Get sensor name.

Get the name of a sensor based on an index. The index should be in the range of 0...Link::GetSensorCount().

Note
A Link does not manage or maintain a pointer to a sensors::Sensor. Access to a Sensor object is accomplished through the sensors::SensorManager. This was done to separate the physics engine from the sensor engine.
Parameters
[in]_indexIndex of the sensor name.
Returns
The name of the sensor, or empty string if the index is out of bounds.
unsigned int GetType ( ) const
inherited

Get the full type definition.

Returns
The full type definition.
msgs::Visual GetVisualMessage ( const std::string &  _name) const

Returns the visual message specified by its name.

Parameters
[in]nameof the visual message
Returns
visual message
const WorldPtr& GetWorld ( ) const
inherited

Get the World this object is in.

Returns
The World this object is part of.
double GetWorldEnergy ( ) const

Returns this link's total energy, or sum of Link::GetWorldEnergyPotential() and Link::GetWorldEnergyKinetic().

Returns
this link's total energy
double GetWorldEnergyKinetic ( ) const

Returns this link's kinetic energy computed using link's CoG velocity in the inertial (world) frame.

Returns
this link's kinetic energy
double GetWorldEnergyPotential ( ) const

Returns this link's potential energy, based on position in world frame and gravity.

Returns
this link's potential energy,
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.
virtual void Init ( )
virtual

Initialize the body.

Reimplemented from Base.

Reimplemented in DARTLink, SimbodyLink, BulletLink, and ODELink.

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

Get the initial relative pose.

Returns
The initial relative pose.
bool IsCanonicalLink ( ) const
inlineinherited

A helper function that checks if this is a canonical body.

Returns
True if the link is canonical.
bool IsSelected ( ) const
inherited

True if the entity is selected by the user.

Returns
True if the entity is selected.
bool IsStatic ( ) const
inherited

Return whether this entity is static.

Returns
True if static.
virtual void Load ( sdf::ElementPtr  _sdf)
virtual

Load the body based on an SDF element.

Parameters
[in]_sdfSDF parameters.

Reimplemented from Entity.

Reimplemented in DARTLink, SimbodyLink, BulletLink, and ODELink.

void MoveFrame ( const ignition::math::Pose3d &  _worldReferenceFrameSrc,
const ignition::math::Pose3d &  _worldReferenceFrameDst,
const bool  _preserveWorldVelocity = false 
)

Move Link given source and target frames specified in world coordinates.

Assuming link's relative pose to source frame (_worldReferenceFrameSrc) remains unchanged relative to destination frame (_worldReferenceFrameDst).

Parameters
[in]_worldReferenceFrameSrcinitial reference frame to which this link is attached.
[in]_worldReferenceFrameDstfinal location of the reference frame specified in world coordinates.
[in]_preserveWorldVelocityTrue if to preserve the world velocity before move frame, default is false.
virtual void OnPoseChange ( )
virtual

This function is called when the entity's (or one of its parents) pose of the parent has changed.

Implements Entity.

Reimplemented in DARTLink, SimbodyLink, BulletLink, and ODELink.

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.
void PlaceOnEntity ( const std::string &  _entityName)
inherited

Move this entity to be ontop of another entity by name.

Parameters
[in]_entityNameName of the Entity this Entity should be ontop of.
void PlaceOnNearestEntityBelow ( )
inherited

Move this entity to be ontop of the nearest entity below.

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

Print this object to screen via gzmsg.

Parameters
[in]_prefixUsually a set of spaces.
void ProcessMsg ( const msgs::Link &  _msg)

Update parameters from a message.

Parameters
[in]_msgMessage to read.
virtual void RegisterIntrospectionItems ( )
protectedvirtual

Register items in the introspection service.

Reimplemented from Base.

ignition::math::Vector3d RelativeAngularAccel ( ) const
virtual

Get the angular acceleration of the body.

Returns
Angular acceleration of the body.

Reimplemented from Entity.

ignition::math::Vector3d RelativeAngularVel ( ) const
virtual

Get the angular velocity of the body.

Returns
Angular velocity of the body.

Reimplemented from Entity.

ignition::math::Vector3d RelativeForce ( ) const

Get the force applied to the body.

Returns
Force applied to the body.
ignition::math::Vector3d RelativeLinearAccel ( ) const
virtual

Get the linear acceleration of the body.

Returns
Linear acceleration of the body.

Reimplemented from Entity.

ignition::math::Vector3d RelativeLinearVel ( ) const
virtual

Get the linear velocity of the body.

Returns
Linear velocity of the body.

Reimplemented from Entity.

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

Get the pose of the entity relative to its parent.

Returns
The pose of the entity relative to its parent.
ignition::math::Vector3d RelativeTorque ( ) const

Get the torque applied to the body.

Returns
Torque applied to the body.
const ignition::math::Vector3d RelativeWindLinearVel ( ) const

Returns this link's wind velocity.

Returns
this link's wind velocity.
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.
virtual void RemoveChild ( EntityPtr  _child)
virtual
void RemoveChildJoint ( const std::string &  _jointName)

Remove Joints that have this Link as a parent Link.

Parameters
[in]_jointNameChild Joint name.
void RemoveChildren ( )
inherited

Remove all children.

void RemoveCollision ( const std::string &  _name)

Remove a collision from the link.

Parameters
int]_name Name of the collision to remove.
void RemoveParentJoint ( const std::string &  _jointName)

Remove Joints that have this Link as a child Link.

Parameters
[in]_jointNameParent Joint name.
void Reset ( )
virtual

Reset the link.

Reimplemented from Entity.

virtual void Reset ( Base::EntityType  _resetType)
virtualinherited

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

Parameters
[in]_resetTypeThe type of reset operation
void ResetPhysicsStates ( )

Reset the velocity, acceleration, force and torque of link.

void SetAngularAccel ( const ignition::math::Vector3d &  _accel)

Set the angular acceleration of the body.

Parameters
[in]_accelAngular acceleration.
Deprecated:
acceleration should be achieved by setting force, see SetForce()
virtual void SetAngularDamping ( double  _damping)
pure virtual

Set the angular damping factor.

Parameters
[in]_dampingAngular damping factor.

Implemented in ODELink, DARTLink, BulletLink, and SimbodyLink.

virtual void SetAngularVel ( const ignition::math::Vector3d &  _vel)
pure virtual

Set the angular velocity of the body.

Parameters
[in]_velAngular velocity.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

void SetAnimation ( const common::PoseAnimationPtr _anim,
boost::function< void()>  _onComplete 
)
inherited

Set an animation for this entity.

Parameters
[in]_animPose animation.
[in]_onCompleteCallback for when the animation completes.
void SetAnimation ( common::PoseAnimationPtr  _anim)
inherited

Set an animation for this entity.

Parameters
[in]_animPose animation.
virtual void SetAutoDisable ( bool  _disable)
pure virtual

Allow the link to auto disable.

Parameters
[in]_disableIf true, the link is allowed to auto disable.

Implemented in ODELink, BulletLink, DARTLink, and SimbodyLink.

void SetCanonicalLink ( bool  _value)
inherited

Set to true if this entity is a canonical link for a model.

Parameters
[in]_valueTrue if the link is canonical.
void SetCollideMode ( const std::string &  _mode)

Set the collide mode of the body.

Parameters
[in]_modeCollision Mode, this can be: [all|none|sensors|fixed|ghost] all: collides with everything none: collides with nothing sensors: collides with everything else but other sensors fixed: collides with everything else but other fixed ghost: collides with everything else but other ghost
virtual void SetEnabled ( bool  _enable) const
pure virtual

Set whether this body is enabled.

Parameters
[in]_enableTrue to enable the link in the physics engine.

Implemented in DARTLink, SimbodyLink, BulletLink, and ODELink.

virtual void SetForce ( const ignition::math::Vector3d &  _force)
pure virtual

Set the force applied to the body.

Parameters
[in]_forceForce value.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

virtual void SetGravityMode ( bool  _mode)
pure virtual

Set whether gravity affects this body.

Parameters
[in]_modeTrue to enable gravity.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

void SetInertial ( const InertialPtr _inertial)

Set the mass of the link.

[in] _inertial Inertial value for the link.

void SetInitialRelativePose ( const ignition::math::Pose3d &  _pose)
inherited

Set the initial pose.

Parameters
[in]_poseThe initial pose.
virtual void SetKinematic ( const bool &  _kinematic)
virtual

Implement this function.

Set whether this body is in the kinematic state.

Parameters
[in]_kinematicTrue to make the link kinematic only.

Reimplemented in ODELink, and DARTLink.

void SetLaserRetro ( float  _retro)

Set the laser retro reflectiveness.

Parameters
[in]_retroRetro value for all child collisions.
void SetLinearAccel ( const ignition::math::Vector3d &  _accel)

Set the linear acceleration of the body.

Parameters
[in]_accelLinear acceleration.
Deprecated:
acceleration should be achieved by setting force, see SetForce()
virtual void SetLinearDamping ( double  _damping)
pure virtual

Set the linear damping factor.

Parameters
[in]_dampingLinear damping factor.

Implemented in ODELink, DARTLink, BulletLink, and SimbodyLink.

virtual void SetLinearVel ( const ignition::math::Vector3d &  _vel)
pure virtual

Set the linear velocity of the body.

Parameters
[in]_velLinear velocity.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

virtual void SetLinkStatic ( bool  _static)
pure virtual

Freeze link to ground (inertial frame).

Parameters
[in]_staticif true, freeze link to ground. Otherwise unfreeze link.

Implemented in ODELink, BulletLink, SimbodyLink, and DARTLink.

virtual void SetName ( const std::string &  _name)
virtualinherited

Set the name of the entity.

Parameters
[in]_nameThe new name.

Reimplemented from Base.

void SetParent ( BasePtr  _parent)
inherited

Set the parent.

Parameters
[in]_parentParent object.
void SetPublishData ( bool  _enable)

Enable/Disable link data publishing.

Parameters
[in]_enableTrue to enable publishing, false to stop publishing
void SetRelativePose ( const ignition::math::Pose3d &  _pose,
const bool  _notify = true,
const bool  _publish = true 
)
inherited

Set the pose of the entity relative to its parent.

Parameters
[in]_poseThe new pose.
[in]_notifyTrue = tell children of the pose change.
[in]_publishTrue to publish the pose.
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.
void SetScale ( const ignition::math::Vector3d &  _scale)

Set the scale of the link.

Parameters
[in]_scaleScale to set the link to.
virtual bool SetSelected ( bool  _set)
virtual

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

Parameters
[in]_setTrue to set the link as selected.

Reimplemented from Base.

virtual void SetSelfCollide ( bool  _collide)
pure virtual

Set whether this body will collide with others in the model.

See Also
GetSelfCollide
Parameters
[in]_collideTrue to enable collisions.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

void SetState ( const LinkState _state)

Set the current link state.

Parameters
[in]_stateThe state to set the link to.
virtual void SetStatic ( const bool &  _static)
virtual
virtual void SetTorque ( const ignition::math::Vector3d &  _torque)
pure virtual

Set the torque applied to the body.

Parameters
[in]_torqueTorque value.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

bool SetVisualPose ( const uint32_t  _id,
const ignition::math::Pose3d &  _pose 
)

Set the pose of a visual.

Parameters
[in]_idUnique ID of visual message.
[in]_posePose relative to this link to place the visual.
Returns
True if setting the pose of the visual was successful.
void SetWindEnabled ( const bool  _enable)

Enable/disable wind for this link.

Parameters
[in]_enableTrue to enable the wind.
virtual void SetWindMode ( const bool  _mode)
virtual

Set whether wind affects this body.

Parameters
[in]_modeTrue to enable wind.
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.
void SetWorldPose ( const ignition::math::Pose3d &  _pose,
const bool  _notify = true,
const bool  _publish = true 
)
inherited

Set the world pose of the entity.

Parameters
[in]_poseThe new world pose.
[in]_notifyTrue = tell children of the pose change.
[in]_publishTrue to publish the pose.
void SetWorldTwist ( const ignition::math::Vector3d &  _linear,
const ignition::math::Vector3d &  _angular,
const bool  _updateChildren = true 
)
inherited

Set angular and linear rates of an physics::Entity.

Parameters
[in]_linearLinear twist.
[in]_angularAngular twist.
[in]_updateChildrenTrue to pass this update to child entities.
virtual void StopAnimation ( )
virtualinherited

Stop the current animation, if any.

Reimplemented in Model.

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 ( const common::UpdateInfo _info)

Update the collision.

Parameters
[in]_infoUpdate information.
virtual void Update ( )
inlinevirtualinherited
virtual void UpdateMass ( )
inlinevirtual

Update the mass matrix.

Reimplemented in SimbodyLink, BulletLink, DARTLink, and ODELink.

virtual void UpdateParameters ( sdf::ElementPtr  _sdf)
virtual

Update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to load from.

Reimplemented from Entity.

virtual void UpdateSurface ( )
inlinevirtual

Update surface parameters.

Reimplemented in ODELink.

void UpdateWind ( const common::UpdateInfo _info)

Update the wind.

Parameters
[in]_infoUpdate information.
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.
bool VisualId ( const std::string &  _visName,
uint32_t &  _visualId 
) const

Get the unique ID of a visual.

Parameters
[in]_visNameName of the visual.
[out]_visualIdThe unique ID of the visual.
Returns
True if getting the unique ID of the visual was successful.
bool VisualPose ( const uint32_t  _id,
ignition::math::Pose3d &  _pose 
) const

Get the pose of a visual.

Parameters
[in]_idUnique ID of visual.
[out]_posePose of the visual relative to this link.
Returns
True if getting the pose of the visual was successful.
virtual bool WindMode ( ) const
virtual

Get the wind mode.

Returns
True if wind is enabled.
ignition::math::Vector3d WorldAngularAccel ( ) const
virtual

Get the angular acceleration of the body in the world frame, which is computed as (I^-1 * (T - w x L)), where I: inertia matrix in world frame T: sum of external torques in world frame L: angular momentum of CoG in world frame w: angular velocity in world frame.

Returns
Angular acceleration of the body in the world frame.

Reimplemented from Entity.

ignition::math::Vector3d WorldAngularMomentum ( ) const

Get the angular momentum of the body CoG in the world frame, which is computed as (I * w), where I: inertia matrix in world frame w: angular velocity in world frame.

Returns
Angular momentum of the body.
virtual ignition::math::Vector3d WorldAngularVel ( ) const
virtualinherited

Get the angular velocity of the entity in the world frame.

Returns
A ignition::math::Vector3d for the velocity.

Reimplemented in Model, Collision, ODELink, DARTLink, SimbodyLink, and BulletLink.

virtual ignition::math::Vector3d WorldCoGLinearVel ( ) const
pure virtual

Get the linear velocity at the body's center of gravity in the world frame.

Returns
Linear velocity at the body's center of gravity in the world frame.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

ignition::math::Pose3d WorldCoGPose ( ) const

Get the pose of the body's center of gravity in the world coordinate frame.

Returns
Pose of the body's center of gravity in the world coordinate frame.
virtual ignition::math::Vector3d WorldForce ( ) const
pure virtual

Get the force applied to the body in the world frame.

Returns
Force applied to the body in the world frame.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

ignition::math::Pose3d WorldInertialPose ( ) const

Get the world pose of the link inertia (cog position and Moment of Inertia frame).

This differs from GetWorldCoGPose(), which returns the cog position in the link frame (not the Moment of Inertia frame).

Returns
Inertial pose in world frame.
ignition::math::Matrix3d WorldInertiaMatrix ( ) const

Get the inertia matrix in the world frame.

Returns
Inertia matrix in world frame, returns matrix of zeros if link has no inertia.
ignition::math::Vector3d WorldLinearAccel ( ) const
virtual

Get the linear acceleration of the body in the world frame.

Returns
Linear acceleration of the body in the world frame.

Reimplemented from Entity.

virtual ignition::math::Vector3d WorldLinearVel ( ) const
virtual

Get the linear velocity of the origin of the link frame, expressed in the world frame.

Returns
Linear velocity of the link frame.

Reimplemented from Entity.

virtual ignition::math::Vector3d WorldLinearVel ( const ignition::math::Vector3d &  _offset) const
pure virtual

Get the linear velocity of a point on the body in the world frame, using an offset expressed in a body-fixed frame.

If no offset is given, the velocity at the origin of the Link frame will be returned.

Parameters
[in]_offsetOffset of the point from the origin of the Link frame, expressed in the body-fixed frame.
Returns
Linear velocity of the point on the body

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

virtual ignition::math::Vector3d WorldLinearVel ( const ignition::math::Vector3d &  _offset,
const ignition::math::Quaterniond &  _q 
) const
pure virtual

Get the linear velocity of a point on the body in the world frame, using an offset expressed in an arbitrary frame.

Parameters
[in]_offsetOffset from the origin of the link frame expressed in a frame defined by _q.
[in]_qDescribes the rotation of a reference frame relative to the world reference frame.
Returns
Linear velocity of the point on the body in the world frame.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

virtual const ignition::math::Pose3d& WorldPose ( ) const
inlinevirtualinherited

Get the absolute pose of the entity.

Returns
The absolute pose of the entity.

Reimplemented in Collision, and Light.

References Entity::worldPose.

virtual ignition::math::Vector3d WorldTorque ( ) const
pure virtual

Get the torque applied to the body about the center of mass in world frame coordinates.

Returns
Torque applied to the body in the world frame.

Implemented in ODELink, DARTLink, SimbodyLink, and BulletLink.

const ignition::math::Vector3d WorldWindLinearVel ( ) const

Returns this link's wind velocity in the world coordinate frame.

Returns
this link's wind velocity.

Member Data Documentation

ignition::math::Vector3d angularAccel
protected

Angular acceleration.

deprecated

common::PoseAnimationPtr animation
protectedinherited

Current pose animation.

event::ConnectionPtr animationConnection
protectedinherited

Connection used to update an animation.

ignition::math::Pose3d animationStartPose
protectedinherited

Start pose of an animation.

std::vector<ignition::math::Pose3d> attachedModelsOffset
protected

Offsets for the attached models.

Base_V children
protectedinherited

Children of this entity.

std::vector<event::ConnectionPtr> connections
protectedinherited

All our event connections.

ignition::math::Pose3d dirtyPose
protectedinherited

The pose set by a physics engine.

InertialPtr inertial
protected

Inertial properties.

Referenced by Link::GetInertial().

bool initialized = false
protected

This flag is set to true when the link is initialized.

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

All the introspection items regsitered for this.

ignition::math::Vector3d linearAccel
protected

Linear acceleration.

deprecated

transport::NodePtr node
protectedinherited

Communication node.

ignition::transport::Node nodeIgn
protectedinherited

Ignition communication node.

BasePtr parent
protectedinherited

Parent of this entity.

EntityPtr parentEntity
protectedinherited

A helper that prevents numerous dynamic_casts.

common::Time prevAnimationTime
protectedinherited

Previous time an animation was updated.

transport::PublisherPtr requestPub
protectedinherited

Request publisher.

ignition::transport::Node::Publisher requestPubIgn
protectedinherited

Request publisher.

ignition::math::Vector3d scale
protectedinherited

Scale of the entity.

sdf::ElementPtr sdf
protectedinherited

The SDF values for this object.

transport::PublisherPtr visPub
protectedinherited

Visual publisher.

ignition::transport::Node::Publisher visPubIgn
protectedinherited

Visual publisher.

msgs::Visual* visualMsg
protectedinherited

Visual message container.

Visuals_M visuals
protected

Link visual elements.

WorldPtr world
protectedinherited

Pointer to the world.

ignition::math::Pose3d worldPose
mutableprotectedinherited

World pose of the entity.

Referenced by Entity::WorldPose().


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