Ignition Gazebo

API Reference

6.1.0

This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a link entity. More...

#include <ignition/gazebo/Link.hh>

Public Member Functions

 Link (gazebo::Entity _entity=kNullEntity)
 Constructor. More...
 
 Link (const Link &_link)
 Copy constructor. More...
 
 Link (Link &&_link) noexcept
 Move constructor. More...
 
 ~Link ()
 Destructor. More...
 
void AddWorldForce (EntityComponentManager &_ecm, const math::Vector3d &_force) const
 Add a force expressed in world coordinates and applied at the center of mass of the link. More...
 
void AddWorldWrench (EntityComponentManager &_ecm, const math::Vector3d &_force, const math::Vector3d &_torque) const
 Add a wrench expressed in world coordinates and applied to the link at the link's origin. This wrench is applied for one simulation step. More...
 
gazebo::Entity CollisionByName (const EntityComponentManager &_ecm, const std::string &_name) const
 Get the ID of a collision entity which is an immediate child of this link. More...
 
uint64_t CollisionCount (const EntityComponentManager &_ecm) const
 Get the number of collisions which are immediate children of this link. More...
 
std::vector< gazebo::EntityCollisions (const EntityComponentManager &_ecm) const
 Get all collisions which are immediate children of this link. More...
 
void EnableAccelerationChecks (EntityComponentManager &_ecm, bool _enable=true) const
 By default, Gazebo will not report accelerations for a link, so functions like WorldLinearAcceleration will return nullopt. This function can be used to enable all acceleration checks. More...
 
void EnableVelocityChecks (EntityComponentManager &_ecm, bool _enable=true) const
 By default, Gazebo will not report velocities for a link, so functions like WorldLinearVelocity will return nullopt. This function can be used to enable all velocity checks. More...
 
gazebo::Entity Entity () const
 Get the entity which this Link is related to. More...
 
bool IsCanonical (const EntityComponentManager &_ecm) const
 Check if this is the canonical link. More...
 
std::optional< std::stringName (const EntityComponentManager &_ecm) const
 Get the link's unscoped name. More...
 
Linkoperator= (Link &&_link) noexcept
 Move assignment operator. More...
 
Linkoperator= (const Link &_link)
 Copy assignment operator. More...
 
std::optional< ModelParentModel (const EntityComponentManager &_ecm) const
 Get the parent model. More...
 
void ResetEntity (gazebo::Entity _newEntity)
 Reset Entity to a new one. More...
 
bool Valid (const EntityComponentManager &_ecm) const
 Check whether this link correctly refers to an entity that has a components::Link. More...
 
gazebo::Entity VisualByName (const EntityComponentManager &_ecm, const std::string &_name) const
 Get the ID of a visual entity which is an immediate child of this link. More...
 
uint64_t VisualCount (const EntityComponentManager &_ecm) const
 Get the number of visuals which are immediate children of this link. More...
 
std::vector< gazebo::EntityVisuals (const EntityComponentManager &_ecm) const
 Get all visuals which are immediate children of this link. More...
 
bool WindMode (const EntityComponentManager &_ecm) const
 Get whether this link has wind enabled. More...
 
std::optional< math::Vector3dWorldAngularVelocity (const EntityComponentManager &_ecm) const
 Get the angular velocity of the link in the world frame. More...
 
std::optional< math::Pose3dWorldInertialPose (const EntityComponentManager &_ecm) const
 Get the world pose of the link inertia. More...
 
std::optional< math::Matrix3dWorldInertiaMatrix (const EntityComponentManager &_ecm) const
 Get the inertia matrix in the world frame. More...
 
std::optional< double > WorldKineticEnergy (const EntityComponentManager &_ecm) const
 Get the rotational and translational kinetic energy of the link with respect to the world frame. More...
 
std::optional< math::Vector3dWorldLinearAcceleration (const EntityComponentManager &_ecm) const
 Get the linear acceleration of the body in the world frame. More...
 
std::optional< math::Vector3dWorldLinearVelocity (const EntityComponentManager &_ecm) const
 Get the linear velocity at the origin of of the link frame expressed 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. More...
 
std::optional< math::Vector3dWorldLinearVelocity (const EntityComponentManager &_ecm, const math::Vector3d &_offset) const
 Get the linear velocity of a point on the body in the world frame, using an offset expressed in a body-fixed frame. More...
 
std::optional< math::Pose3dWorldPose (const EntityComponentManager &_ecm) const
 Get the pose of the link frame in the world coordinate frame. More...
 

Detailed Description

This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a link entity.

For example, given a link's entity, to find the value of its name component, one could use the entity-component manager (ecm) directly as follows:

std::string name = ecm.Component<components::Name>(entity)->Data();

Using this class however, the same information can be obtained with a simpler function call:

Link link(entity); std::string name = link.Name(ecm);

Constructor & Destructor Documentation

◆ Link() [1/3]

Link ( gazebo::Entity  _entity = kNullEntity)
explicit

Constructor.

Parameters
[in]_entityLink entity

◆ Link() [2/3]

Link ( const Link _link)

Copy constructor.

Parameters
[in]_linkLink to copy.

◆ Link() [3/3]

Link ( Link &&  _link)
noexcept

Move constructor.

Parameters
[in]_linkLink to move.

◆ ~Link()

~Link ( )

Destructor.

Member Function Documentation

◆ AddWorldForce()

void AddWorldForce ( EntityComponentManager _ecm,
const math::Vector3d _force 
) const

Add a force expressed in world coordinates and applied at the center of mass of the link.

Parameters
[in]_ecmMutable Entity-component manager.
[in]_forceForce to be applied expressed in world coordinates

◆ AddWorldWrench()

void AddWorldWrench ( EntityComponentManager _ecm,
const math::Vector3d _force,
const math::Vector3d _torque 
) const

Add a wrench expressed in world coordinates and applied to the link at the link's origin. This wrench is applied for one simulation step.

Parameters
[in]_ecmMutable Entity-component manager.
[in]_forceForce to be applied expressed in world coordinates
[in]_torqueTorque to be applied expressed in world coordinates

◆ CollisionByName()

gazebo::Entity CollisionByName ( const EntityComponentManager _ecm,
const std::string _name 
) const

Get the ID of a collision entity which is an immediate child of this link.

Parameters
[in]_ecmEntity-component manager.
[in]_nameCollision name.
Returns
Collision entity.

◆ CollisionCount()

uint64_t CollisionCount ( const EntityComponentManager _ecm) const

Get the number of collisions which are immediate children of this link.

Parameters
[in]_ecmEntity-component manager.
Returns
Number of collisions in this link.

◆ Collisions()

std::vector<gazebo::Entity> Collisions ( const EntityComponentManager _ecm) const

Get all collisions which are immediate children of this link.

Parameters
[in]_ecmEntity-component manager.
Returns
All collisions in this link.

◆ EnableAccelerationChecks()

void EnableAccelerationChecks ( EntityComponentManager _ecm,
bool  _enable = true 
) const

By default, Gazebo will not report accelerations for a link, so functions like WorldLinearAcceleration will return nullopt. This function can be used to enable all acceleration checks.

Parameters
[in]_ecmMutable reference to the ECM.
[in]_enableTrue to enable checks, false to disable. Defaults to true.

◆ EnableVelocityChecks()

void EnableVelocityChecks ( EntityComponentManager _ecm,
bool  _enable = true 
) const

By default, Gazebo will not report velocities for a link, so functions like WorldLinearVelocity will return nullopt. This function can be used to enable all velocity checks.

Parameters
[in]_ecmMutable reference to the ECM.
[in]_enableTrue to enable checks, false to disable. Defaults to true.

◆ Entity()

Get the entity which this Link is related to.

Returns
Link entity.

◆ IsCanonical()

bool IsCanonical ( const EntityComponentManager _ecm) const

Check if this is the canonical link.

Parameters
[in]_ecmEntity-component manager.
Returns
True if it is the canonical link.

◆ Name()

std::optional<std::string> Name ( const EntityComponentManager _ecm) const

Get the link's unscoped name.

Parameters
[in]_ecmEntity-component manager.
Returns
Link's name or nullopt if the entity does not have a components::Name component

◆ operator=() [1/2]

Link& operator= ( Link &&  _link)
noexcept

Move assignment operator.

Parameters
[in]_linkLink component to move.
Returns
Reference to this.

◆ operator=() [2/2]

Link& operator= ( const Link _link)

Copy assignment operator.

Parameters
[in]_linkLink to copy.
Returns
Reference to this.

◆ ParentModel()

std::optional<Model> ParentModel ( const EntityComponentManager _ecm) const

Get the parent model.

Parameters
[in]_ecmEntity-component manager.
Returns
Parent Model or nullopt if the entity does not have a components::ParentEntity component.

◆ ResetEntity()

void ResetEntity ( gazebo::Entity  _newEntity)

Reset Entity to a new one.

Parameters
[in]_newEntityNew link entity.

◆ Valid()

bool Valid ( const EntityComponentManager _ecm) const

Check whether this link correctly refers to an entity that has a components::Link.

Parameters
[in]_ecmEntity-component manager.
Returns
True if it's a valid link in the manager.

◆ VisualByName()

gazebo::Entity VisualByName ( const EntityComponentManager _ecm,
const std::string _name 
) const

Get the ID of a visual entity which is an immediate child of this link.

Parameters
[in]_ecmEntity-component manager.
[in]_nameVisual name.
Returns
Visual entity.

◆ VisualCount()

uint64_t VisualCount ( const EntityComponentManager _ecm) const

Get the number of visuals which are immediate children of this link.

Parameters
[in]_ecmEntity-component manager.
Returns
Number of visuals in this link.

◆ Visuals()

std::vector<gazebo::Entity> Visuals ( const EntityComponentManager _ecm) const

Get all visuals which are immediate children of this link.

Parameters
[in]_ecmEntity-component manager.
Returns
All visuals in this link.

◆ WindMode()

bool WindMode ( const EntityComponentManager _ecm) const

Get whether this link has wind enabled.

Parameters
[in]_ecmEntity-component manager.
Returns
True if wind mode is on.

◆ WorldAngularVelocity()

std::optional<math::Vector3d> WorldAngularVelocity ( const EntityComponentManager _ecm) const

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

Parameters
[in]_ecmEntity-component manager.
Returns
Angular velocity of the link or nullopt if velocity checks aren't enabled.
See also
EnableVelocityChecks

◆ WorldInertialPose()

std::optional<math::Pose3d> WorldInertialPose ( const EntityComponentManager _ecm) const

Get the world pose of the link inertia.

Parameters
[in]_ecmEntity-component manager.
Returns
Inertial pose in world frame or nullopt if the link does not have the components components::WorldPose and components::Inertial.

◆ WorldInertiaMatrix()

std::optional<math::Matrix3d> WorldInertiaMatrix ( const EntityComponentManager _ecm) const

Get the inertia matrix in the world frame.

Parameters
[in]_ecmEntity-component manager.
Returns
Inertia matrix in world frame, returns nullopt if link does not have components components::Inertial and components::WorldPose.

◆ WorldKineticEnergy()

std::optional<double> WorldKineticEnergy ( const EntityComponentManager _ecm) const

Get the rotational and translational kinetic energy of the link with respect to the world frame.

Parameters
[in]_ecmEntity-component manager.
Returns
Kinetic energy in world frame, returns nullopt if link does not have components components::Inertial, components::WorldAngularVelocity, components::WorldLinearVelocity, and components::WorldPose.

◆ WorldLinearAcceleration()

std::optional<math::Vector3d> WorldLinearAcceleration ( const EntityComponentManager _ecm) const

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

Parameters
[in]_ecmEntity-component manager.
Returns
Linear acceleration of the body in the world frame or nullopt if acceleration checks aren't enabled.
See also
EnableAccelerationChecks

◆ WorldLinearVelocity() [1/2]

std::optional<math::Vector3d> WorldLinearVelocity ( const EntityComponentManager _ecm) const

Get the linear velocity at the origin of of the link frame expressed 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]_ecmEntity-component manager.
Returns
Linear velocity of the link or nullopt if the velocity checks aren't enabled.
See also
EnableVelocityChecks

◆ WorldLinearVelocity() [2/2]

std::optional<math::Vector3d> WorldLinearVelocity ( const EntityComponentManager _ecm,
const math::Vector3d _offset 
) const

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

Parameters
[in]_ecmEntity-component manager.
[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 or nullopt if velocity checks aren't enabled.
See also
EnableVelocityChecks

◆ WorldPose()

std::optional<math::Pose3d> WorldPose ( const EntityComponentManager _ecm) const

Get the pose of the link frame in the world coordinate frame.

Parameters
[in]_ecmEntity-component manager.
Returns
Absolute Pose of the link or nullopt if the entity does not have a components::WorldPose component.

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