Link class defines a rigid body entity, containing information on inertia, visual and collision properties of a rigid body. More...
#include <physics/physics.hh>
Public Member Functions | |
Link (EntityPtr _parent) | |
Constructor. More... | |
virtual | ~Link () |
Destructor. More... | |
void | AddChildJoint (JointPtr _joint) |
Joints that have this Link as a parent Link. More... | |
virtual void | AddForce (const math::Vector3 &_force)=0 |
Add a force to the body. More... | |
virtual void | AddForceAtRelativePosition (const math::Vector3 &_force, const math::Vector3 &_relPos)=0 |
Add a force to the body at position expressed to the body's own frame of reference. More... | |
virtual void | AddForceAtWorldPosition (const math::Vector3 &_force, const math::Vector3 &_pos)=0 |
Add a force to the body using a global position. More... | |
void | AddParentJoint (JointPtr _joint) |
Joints that have this Link as a child Link. More... | |
virtual void | AddRelativeForce (const math::Vector3 &_force)=0 |
Add a force to the body, components are relative to the body's own frame of reference. More... | |
virtual void | AddRelativeTorque (const math::Vector3 &_torque)=0 |
Add a torque to the body, components are relative to the body's own frame of reference. More... | |
virtual void | AddTorque (const math::Vector3 &_torque)=0 |
Add a torque to the body. More... | |
void | AttachStaticModel (ModelPtr &_model, const math::Pose &_offset) |
Attach a static model to this link. More... | |
template<typename T > | |
event::ConnectionPtr | ConnectEnabled (T _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... | |
void | DisconnectEnabled (event::ConnectionPtr &_conn) |
Disconnect to the add entity signal. 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... | |
virtual math::Box | GetBoundingBox () const |
Get the bounding box for the link and all the child elements. More... | |
Joint_V | GetChildJoints () const |
Get the child joints. More... | |
Link_V | GetChildJointsLinks () const |
Returns a vector of children Links connected by joints. 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... | |
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... | |
Joint_V | GetParentJoints () const |
Get the parent joints. More... | |
Link_V | GetParentJointsLinks () const |
Returns a vector of parent Links connected by joints. More... | |
math::Vector3 | GetRelativeAngularAccel () const |
Get the angular acceleration of the body. More... | |
math::Vector3 | GetRelativeAngularVel () const |
Get the angular velocity of the body. More... | |
math::Vector3 | GetRelativeForce () const |
Get the force applied to the body. More... | |
math::Vector3 | GetRelativeLinearAccel () const |
Get the linear acceleration of the body. More... | |
math::Vector3 | GetRelativeLinearVel () const |
Get the linear velocity of the body. More... | |
math::Vector3 | GetRelativeTorque () const |
Get the torque applied to the body. More... | |
bool | GetSelfCollide () const |
Get Self-Collision Flag, if this is true, this body will collide with other bodies even if they share the same parent. More... | |
unsigned int | GetSensorCount () const |
Get sensor count. More... | |
std::string | GetSensorName (unsigned int _index) const |
Get sensor name. More... | |
msgs::Visual | GetVisualMessage (const std::string &_name) const |
Returns the visual message specified by its name. More... | |
math::Vector3 | GetWorldAngularAccel () const |
Get the angular acceleration of the body in the world frame. More... | |
virtual math::Vector3 | GetWorldCoGLinearVel () const =0 |
Get the linear velocity at the body's center of gravity in the world frame. More... | |
math::Pose | GetWorldCoGPose () const |
Get the pose of the body's center of gravity in the world coordinate frame. 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... | |
virtual math::Vector3 | GetWorldForce () const =0 |
Get the force applied to the body in the world frame. More... | |
math::Pose | GetWorldInertialPose () const |
Get the world pose of the link inertia (cog position and Moment of Inertia frame). More... | |
math::Matrix3 | GetWorldInertiaMatrix () const |
Get the inertia matrix in the world frame. More... | |
math::Vector3 | GetWorldLinearAccel () const |
Get the linear acceleration of the body in the world frame. More... | |
virtual math::Vector3 | GetWorldLinearVel () const |
Get the linear velocity of the origin of the link frame, expressed in the world frame. More... | |
virtual math::Vector3 | GetWorldLinearVel (const math::Vector3 &_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 math::Vector3 | GetWorldLinearVel (const math::Vector3 &_offset, const math::Quaternion &_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 math::Vector3 | GetWorldTorque () const =0 |
Get the torque applied to the body in the world frame. More... | |
virtual void | Init () |
Initialize the body. More... | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load the body based on an SDF element. More... | |
void | MoveFrame (const math::Pose &_worldReferenceFrameSrc, const math::Pose &_worldReferenceFrameDst) |
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... | |
void | ProcessMsg (const msgs::Link &_msg) |
Update parameters from a message. More... | |
virtual void | RemoveChild (EntityPtr _child) |
void | RemoveChildJoint (const std::string &_jointName) |
Remove Joints that have this Link as a parent Link. 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... | |
void | ResetPhysicsStates () |
Reset the link. More... | |
void | SetAngularAccel (const math::Vector3 &_accel) |
Set the angular acceleration of the body. More... | |
virtual void | SetAngularDamping (double _damping)=0 |
Set the angular damping factor. More... | |
virtual void | SetAngularVel (const math::Vector3 &_vel)=0 |
Set the angular velocity of the body. More... | |
virtual void | SetAutoDisable (bool _disable)=0 |
Allow the link to auto disable. 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 math::Vector3 &_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... | |
virtual void | SetKinematic (const bool &_kinematic) |
Implement this function. More... | |
void | SetLaserRetro (float _retro) |
Set the laser retro reflectiveness. More... | |
void | SetLinearAccel (const math::Vector3 &_accel) |
Set the linear acceleration of the body. More... | |
virtual void | SetLinearDamping (double _damping)=0 |
Set the linear damping factor. More... | |
virtual void | SetLinearVel (const math::Vector3 &_vel)=0 |
Set the linear velocity of the body. More... | |
virtual void | SetLinkStatic (bool _static)=0 |
Freeze link to ground (inertial frame). More... | |
void | SetPublishData (bool _enable) |
Enable/Disable link data publishing. More... | |
void | SetScale (const math::Vector3 &_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 | SetTorque (const math::Vector3 &_torque)=0 |
Set the torque applied to the body. More... | |
void | Update (const common::UpdateInfo &_info) |
Update the collision. 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... | |
Public Member Functions inherited from gazebo::physics::Entity | |
Entity (BasePtr _parent) | |
Constructor. More... | |
virtual | ~Entity () |
Destructor. More... | |
CollisionPtr | GetChildCollision (const std::string &_name) |
Get a child collision entity, if one exists. More... | |
LinkPtr | GetChildLink (const std::string &_name) |
Get a child linke entity, if one exists. More... | |
math::Box | GetCollisionBoundingBox () const |
Returns collision bounding box. More... | |
const math::Pose & | GetDirtyPose () const |
Returns Entity::dirtyPose. More... | |
math::Pose | GetInitialRelativePose () const |
Get the initial relative pose. More... | |
void | GetNearestEntityBelow (double &_distBelow, std::string &_entityName) |
Get the distance to the nearest entity below (along the Z-axis) this entity. More... | |
ModelPtr | GetParentModel () |
Get the parent model, if one exists. More... | |
math::Pose | GetRelativePose () const |
Get the pose of the entity relative to its parent. More... | |
virtual math::Vector3 | GetWorldAngularVel () const |
Get the angular velocity of the entity in the world frame. More... | |
virtual const math::Pose & | GetWorldPose () const |
Get the absolute pose of the entity. More... | |
bool | IsCanonicalLink () const |
A helper function that checks if this is a canonical body. More... | |
bool | IsStatic () const |
Return whether this entity is static. 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 | 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... | |
void | SetCanonicalLink (bool _value) |
Set to true if this entity is a canonical link for a model. More... | |
void | SetInitialRelativePose (const math::Pose &_pose) |
Set the initial pose. More... | |
virtual void | SetName (const std::string &_name) |
Set the name of the entity. More... | |
void | SetRelativePose (const math::Pose &_pose, bool _notify=true, bool _publish=true) |
Set the pose of the entity relative to its parent. More... | |
void | SetStatic (const bool &_static) |
Set whether this entity is static: immovable. More... | |
void | SetWorldPose (const math::Pose &_pose, bool _notify=true, bool _publish=true) |
Set the world pose of the entity. More... | |
void | SetWorldTwist (const math::Vector3 &_linear, const math::Vector3 &_angular, bool _updateChildren=true) |
Set angular and linear rates of an physics::Entity. More... | |
virtual void | StopAnimation () |
Stop the current animation, if any. More... | |
Public Member Functions inherited from gazebo::physics::Base | |
Base (BasePtr _parent) | |
Constructor. More... | |
virtual | ~Base () |
Destructor. More... | |
void | AddChild (BasePtr _child) |
Add a child to this entity. More... | |
void | AddType (EntityType _type) |
Add a type specifier. More... | |
BasePtr | GetByName (const std::string &_name) |
Get by name. More... | |
BasePtr | GetChild (unsigned int _i) const |
Get a child by index. More... | |
BasePtr | GetChild (const std::string &_name) |
Get a child by name. More... | |
unsigned int | GetChildCount () const |
Get the number of children. More... | |
uint32_t | GetId () const |
Return the ID of this entity. More... | |
std::string | GetName () const |
Return the name of the entity. More... | |
BasePtr | GetParent () const |
Get the parent. More... | |
int | GetParentId () const |
Return the ID of the parent. More... | |
bool | GetSaveable () const |
Get whether the object should be "saved", when the user selects to save the world to xml. More... | |
std::string | GetScopedName (bool _prependWorldName=false) const |
Return the name of this entity with the model scope model1::...::modelN::entityName. More... | |
virtual const sdf::ElementPtr | GetSDF () |
Get the SDF values for the object. More... | |
unsigned int | GetType () const |
Get the full type definition. More... | |
const WorldPtr & | GetWorld () const |
Get the World this object is in. More... | |
bool | HasType (const EntityType &_t) const |
Returns true if this object's type definition has the given type. More... | |
bool | IsSelected () const |
True if the entity is selected by the user. More... | |
bool | operator== (const Base &_ent) const |
Returns true if the entities are the same. More... | |
void | Print (const std::string &_prefix) |
Print this object to screen via gzmsg. More... | |
virtual void | RemoveChild (unsigned int _id) |
Remove a child from this entity. More... | |
void | RemoveChild (const std::string &_name) |
Remove a child by name. More... | |
void | RemoveChildren () |
Remove all children. More... | |
virtual void | Reset (Base::EntityType _resetType) |
Calls recursive Reset on one of the Base::EntityType's. More... | |
void | SetParent (BasePtr _parent) |
Set the parent. More... | |
void | SetSaveable (bool _v) |
Set whether the object should be "saved", when the user selects to save the world to xml. More... | |
void | SetWorld (const WorldPtr &_newWorld) |
Set the world this object belongs to. More... | |
virtual void | Update () |
Update the object. More... | |
Protected Types | |
typedef std::map< uint32_t, msgs::Visual > | Visuals_M |
Protected Attributes | |
math::Vector3 | angularAccel |
Angular acceleration. More... | |
std::vector< math::Pose > | attachedModelsOffset |
Offsets for the attached models. More... | |
std::vector< std::string > | cgVisuals |
Center of gravity visual elements. More... | |
InertialPtr | inertial |
Inertial properties. More... | |
bool | initialized |
This flag is set to true when the link is initialized. More... | |
math::Vector3 | linearAccel |
Linear acceleration. More... | |
Visuals_M | visuals |
Link visual elements. More... | |
Protected Attributes inherited from gazebo::physics::Entity | |
common::PoseAnimationPtr | animation |
Current pose animation. More... | |
event::ConnectionPtr | animationConnection |
Connection used to update an animation. More... | |
math::Pose | animationStartPose |
Start pose of an animation. More... | |
std::vector< event::ConnectionPtr > | connections |
All our event connections. More... | |
math::Pose | dirtyPose |
The pose set by a physics engine. More... | |
transport::NodePtr | node |
Communication node. 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... | |
math::Vector3 | scale |
Scale of the entity. More... | |
transport::PublisherPtr | visPub |
Visual publisher. More... | |
msgs::Visual * | visualMsg |
Visual message container. More... | |
math::Pose | worldPose |
World pose of the entity. More... | |
Protected Attributes inherited from gazebo::physics::Base | |
Base_V | children |
Children of this entity. More... | |
BasePtr | parent |
Parent of this entity. More... | |
sdf::ElementPtr | sdf |
The SDF values for this object. More... | |
WorldPtr | world |
Pointer to the world. More... | |
Additional Inherited Members | |
Public Types inherited from gazebo::physics::Base | |
enum | EntityType { BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004, COLLISION = 0x00000008, ACTOR = 0x00000016, LIGHT = 0x00000010, VISUAL = 0x00000020, JOINT = 0x00000040, BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200, SLIDER_JOINT = 0x00000400, SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, GEARBOX_JOINT = 0x00002000, SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000, HEIGHTMAP_SHAPE = 0x00080000, MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000, PLANE_SHAPE = 0x00800000, SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000, SENSOR_COLLISION = 0x10000000 } |
Unique identifiers for all entity types. More... | |
Protected Member Functions inherited from gazebo::physics::Base | |
void | ComputeScopedName () |
Compute the scoped name of this object based on its parents. More... | |
Link class defines a rigid body entity, containing information on inertia, visual and collision properties of a rigid body.
|
protected |
|
explicit |
Constructor.
[in] | _parent | Parent of this link. |
|
virtual |
Destructor.
void gazebo::physics::Link::AddChildJoint | ( | JointPtr | _joint | ) |
|
pure virtual |
Add a force to the body.
[in] | _force | Force to add. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, gazebo::physics::ODELink, and gazebo::physics::DARTLink.
|
pure virtual |
Add a force to the body at position expressed to the body's own frame of reference.
[in] | _force | Force to add. |
[in] | _relPos | Position on the link to add the force. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, gazebo::physics::ODELink, and gazebo::physics::DARTLink.
|
pure virtual |
Add a force to the body using a global position.
[in] | _force | Force to add. |
[in] | _pos | Position in global coord frame to add the force. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, gazebo::physics::ODELink, and gazebo::physics::DARTLink.
void gazebo::physics::Link::AddParentJoint | ( | JointPtr | _joint | ) |
|
pure virtual |
Add a force to the body, components are relative to the body's own frame of reference.
[in] | _force | Force to add. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, gazebo::physics::ODELink, and gazebo::physics::DARTLink.
|
pure virtual |
Add a torque to the body, components are relative to the body's own frame of reference.
[in] | _torque | Torque value to add. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, gazebo::physics::ODELink, and gazebo::physics::DARTLink.
|
pure virtual |
Add a torque to the body.
[in] | _torque | Torque value to add to the link. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, gazebo::physics::ODELink, and gazebo::physics::DARTLink.
void gazebo::physics::Link::AttachStaticModel | ( | ModelPtr & | _model, |
const math::Pose & | _offset | ||
) |
Attach a static model to this link.
[in] | _model | Pointer to a static model. |
[in] | _offset | Pose relative to this link to place the model. |
|
inline |
Connect to the add entity signal.
[in] | _subscriber | Subsciber callback function. |
void gazebo::physics::Link::DetachAllStaticModels | ( | ) |
Detach all static models from this link.
void gazebo::physics::Link::DetachStaticModel | ( | const std::string & | _modelName | ) |
Detach a static model from this link.
[in] | _modelName | Name of an attached model to detach. |
|
inline |
Disconnect to the add entity signal.
[in] | _conn | Connection pointer to disconnect. |
void gazebo::physics::Link::FillMsg | ( | msgs::Link & | _msg | ) |
Fill a link message.
[out] | _msg | Message to fill |
bool gazebo::physics::Link::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.
[in] | _originParentLink | if this link is a child link of the search, we've found a loop. |
in/out] | _connectedLinks aggregate list of connected links. | |
[in] | _fistLink | this is the first Link, skip over the parent link that matches the _originalParentLink. |
|
virtual |
Finalize the body.
Reimplemented from gazebo::physics::Entity.
Reimplemented in gazebo::physics::SimbodyLink, and gazebo::physics::ODELink.
double gazebo::physics::Link::GetAngularDamping | ( | ) | const |
Get the angular damping factor.
|
virtual |
Get the bounding box for the link and all the child elements.
Reimplemented from gazebo::physics::Entity.
Joint_V gazebo::physics::Link::GetChildJoints | ( | ) | const |
Get the child joints.
Link_V gazebo::physics::Link::GetChildJointsLinks | ( | ) | const |
Returns a vector of children Links connected by joints.
CollisionPtr gazebo::physics::Link::GetCollision | ( | const std::string & | _name | ) |
Get a child collision by name.
[in] | _name | Name of the collision object. |
CollisionPtr gazebo::physics::Link::GetCollision | ( | unsigned int | _index | ) | const |
Get a child collision by index.
[in] | _index | Index of the collision object. |
Collision_V gazebo::physics::Link::GetCollisions | ( | ) | const |
Get all the child collisions.
|
pure virtual |
Get whether this body is enabled in the physics engine.
Implemented in gazebo::physics::BulletLink, gazebo::physics::DARTLink, gazebo::physics::SimbodyLink, and gazebo::physics::ODELink.
|
pure virtual |
Get the gravity mode.
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
|
inline |
Get the inertia of the link.
|
inlinevirtual |
Implement this function.
Get whether this body is in the kinematic state.
Reimplemented in gazebo::physics::ODELink, and gazebo::physics::DARTLink.
double gazebo::physics::Link::GetLinearDamping | ( | ) | const |
Get the linear damping factor.
ModelPtr gazebo::physics::Link::GetModel | ( | ) | const |
Get the model that this body belongs to.
Joint_V gazebo::physics::Link::GetParentJoints | ( | ) | const |
Get the parent joints.
Link_V gazebo::physics::Link::GetParentJointsLinks | ( | ) | const |
Returns a vector of parent Links connected by joints.
|
virtual |
Get the angular acceleration of the body.
Reimplemented from gazebo::physics::Entity.
|
virtual |
Get the angular velocity of the body.
Reimplemented from gazebo::physics::Entity.
math::Vector3 gazebo::physics::Link::GetRelativeForce | ( | ) | const |
Get the force applied to the body.
|
virtual |
Get the linear acceleration of the body.
Reimplemented from gazebo::physics::Entity.
|
virtual |
Get the linear velocity of the body.
Reimplemented from gazebo::physics::Entity.
math::Vector3 gazebo::physics::Link::GetRelativeTorque | ( | ) | const |
Get the torque applied to the body.
bool gazebo::physics::Link::GetSelfCollide | ( | ) | const |
Get Self-Collision Flag, if this is true, this body will collide with other bodies even if they share the same parent.
unsigned int gazebo::physics::Link::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.
std::string gazebo::physics::Link::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().
[in] | _index | Index of the sensor name. |
msgs::Visual gazebo::physics::Link::GetVisualMessage | ( | const std::string & | _name | ) | const |
Returns the visual message specified by its name.
[in] | name | of the visual message |
|
virtual |
Get the angular acceleration of the body in the world frame.
Reimplemented from gazebo::physics::Entity.
|
pure virtual |
Get the linear velocity at the body's center of gravity in the world frame.
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
math::Pose gazebo::physics::Link::GetWorldCoGPose | ( | ) | const |
Get the pose of the body's center of gravity in the world coordinate frame.
double gazebo::physics::Link::GetWorldEnergy | ( | ) | const |
Returns this link's total energy, or sum of Link::GetWorldEnergyPotential() and Link::GetWorldEnergyKinetic().
double gazebo::physics::Link::GetWorldEnergyKinetic | ( | ) | const |
Returns this link's kinetic energy computed using link's CoG velocity in the inertial (world) frame.
double gazebo::physics::Link::GetWorldEnergyPotential | ( | ) | const |
Returns this link's potential energy, based on position in world frame and gravity.
|
pure virtual |
Get the force applied to the body in the world frame.
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
math::Pose gazebo::physics::Link::GetWorldInertialPose | ( | ) | 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).
math::Matrix3 gazebo::physics::Link::GetWorldInertiaMatrix | ( | ) | const |
Get the inertia matrix in the world frame.
|
virtual |
Get the linear acceleration of the body in the world frame.
Reimplemented from gazebo::physics::Entity.
|
inlinevirtual |
Get the linear velocity of the origin of the link frame, expressed in the world frame.
Reimplemented from gazebo::physics::Entity.
References gazebo::math::Vector3::Zero.
|
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.
[in] | _offset | Offset of the point from the origin of the Link frame, expressed in the body-fixed frame. |
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Get the linear velocity of a point on the body in the world frame, using an offset expressed in an arbitrary frame.
[in] | _offset | Offset from the origin of the link frame expressed in a frame defined by _q. |
[in] | _q | Describes the rotation of a reference frame relative to the world reference frame. |
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Get the torque applied to the body in the world frame.
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
|
virtual |
Initialize the body.
Reimplemented from gazebo::physics::Base.
Reimplemented in gazebo::physics::BulletLink, gazebo::physics::DARTLink, gazebo::physics::SimbodyLink, and gazebo::physics::ODELink.
|
virtual |
Load the body based on an SDF element.
[in] | _sdf | SDF parameters. |
Reimplemented from gazebo::physics::Entity.
Reimplemented in gazebo::physics::BulletLink, gazebo::physics::DARTLink, gazebo::physics::SimbodyLink, and gazebo::physics::ODELink.
void gazebo::physics::Link::MoveFrame | ( | const math::Pose & | _worldReferenceFrameSrc, |
const math::Pose & | _worldReferenceFrameDst | ||
) |
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).
[in] | _worldReferenceFrameSrc | initial reference frame to which this link is attached. |
[in] | _worldReferenceFrameDst | final location of the reference frame specified in world coordinates. |
|
virtual |
This function is called when the entity's (or one of its parents) pose of the parent has changed.
Implements gazebo::physics::Entity.
Reimplemented in gazebo::physics::BulletLink, gazebo::physics::DARTLink, gazebo::physics::SimbodyLink, and gazebo::physics::ODELink.
void gazebo::physics::Link::ProcessMsg | ( | const msgs::Link & | _msg | ) |
Update parameters from a message.
[in] | _msg | Message to read. |
|
virtual |
void gazebo::physics::Link::RemoveChildJoint | ( | const std::string & | _jointName | ) |
void gazebo::physics::Link::RemoveCollision | ( | const std::string & | _name | ) |
Remove a collision from the link.
int] | _name Name of the collision to remove. |
void gazebo::physics::Link::RemoveParentJoint | ( | const std::string & | _jointName | ) |
|
virtual |
Reset the link.
Reimplemented from gazebo::physics::Entity.
void gazebo::physics::Link::ResetPhysicsStates | ( | ) |
Reset the link.
void gazebo::physics::Link::SetAngularAccel | ( | const math::Vector3 & | _accel | ) |
Set the angular acceleration of the body.
[in] | _accel | Angular acceleration. |
|
pure virtual |
Set the angular damping factor.
[in] | _damping | Angular damping factor. |
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Set the angular velocity of the body.
[in] | _vel | Angular velocity. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::ODELink, gazebo::physics::DARTLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Allow the link to auto disable.
[in] | _disable | If true, the link is allowed to auto disable. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::ODELink, gazebo::physics::DARTLink, and gazebo::physics::SimbodyLink.
void gazebo::physics::Link::SetCollideMode | ( | const std::string & | _mode | ) |
Set the collide mode of the body.
[in] | _mode | Collision 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 |
|
pure virtual |
Set whether this body is enabled.
[in] | _enable | True to enable the link in the physics engine. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::DARTLink, gazebo::physics::SimbodyLink, and gazebo::physics::ODELink.
|
pure virtual |
Set the force applied to the body.
[in] | _force | Force value. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::ODELink, gazebo::physics::DARTLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Set whether gravity affects this body.
[in] | _mode | True to enable gravity. |
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
void gazebo::physics::Link::SetInertial | ( | const InertialPtr & | _inertial | ) |
Set the mass of the link.
[in] _inertial Inertial value for the link.
|
virtual |
Implement this function.
Set whether this body is in the kinematic state.
[in] | _kinematic | True to make the link kinematic only. |
Reimplemented in gazebo::physics::ODELink, and gazebo::physics::DARTLink.
void gazebo::physics::Link::SetLaserRetro | ( | float | _retro | ) |
Set the laser retro reflectiveness.
[in] | _retro | Retro value for all child collisions. |
void gazebo::physics::Link::SetLinearAccel | ( | const math::Vector3 & | _accel | ) |
Set the linear acceleration of the body.
[in] | _accel | Linear acceleration. |
|
pure virtual |
Set the linear damping factor.
[in] | _damping | Linear damping factor. |
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Set the linear velocity of the body.
[in] | _vel | Linear velocity. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::ODELink, gazebo::physics::DARTLink, and gazebo::physics::SimbodyLink.
|
pure virtual |
Freeze link to ground (inertial frame).
[in] | _static | if true, freeze link to ground. Otherwise unfreeze link. |
Implemented in gazebo::physics::ODELink, gazebo::physics::BulletLink, gazebo::physics::SimbodyLink, and gazebo::physics::DARTLink.
void gazebo::physics::Link::SetPublishData | ( | bool | _enable | ) |
Enable/Disable link data publishing.
[in] | _enable | True to enable publishing, false to stop publishing |
void gazebo::physics::Link::SetScale | ( | const math::Vector3 & | _scale | ) |
Set the scale of the link.
[in] | _scale | Scale to set the link to. |
|
virtual |
Set whether this entity has been selected by the user through the gui.
[in] | _set | True to set the link as selected. |
Reimplemented from gazebo::physics::Base.
|
pure virtual |
Set whether this body will collide with others in the model.
[in] | _collid | True to enable collisions. |
Implemented in gazebo::physics::ODELink, gazebo::physics::DARTLink, gazebo::physics::BulletLink, and gazebo::physics::SimbodyLink.
void gazebo::physics::Link::SetState | ( | const LinkState & | _state | ) |
Set the current link state.
[in] | _state | The state to set the link to. |
|
pure virtual |
Set the torque applied to the body.
[in] | _torque | Torque value. |
Implemented in gazebo::physics::BulletLink, gazebo::physics::ODELink, gazebo::physics::DARTLink, and gazebo::physics::SimbodyLink.
void gazebo::physics::Link::Update | ( | const common::UpdateInfo & | _info | ) |
Update the collision.
[in] | _info | Update information. |
|
inlinevirtual |
Update the mass matrix.
Reimplemented in gazebo::physics::ODELink.
|
virtual |
Update the parameters using new sdf values.
[in] | _sdf | SDF values to load from. |
Reimplemented from gazebo::physics::Entity.
|
inlinevirtual |
Update surface parameters.
Reimplemented in gazebo::physics::ODELink.
|
protected |
Angular acceleration.
|
protected |
Offsets for the attached models.
|
protected |
Center of gravity visual elements.
|
protected |
Inertial properties.
|
protected |
This flag is set to true when the link is initialized.
|
protected |
Linear acceleration.