gz/sim/Link.hh
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light....
Definition: gz/sim/Entity.hh:59
This library is part of the Ignition Robotics project.
STL class.
The EntityComponentManager constructs, deletes, and returns components and entities....
Definition: gz/sim/EntityComponentManager.hh:65
STL class.
std::optional< Model > ParentModel(const EntityComponentManager &_ecm) const
Get the parent model.
uint64_t VisualCount(const EntityComponentManager &_ecm) const
Get the number of visuals which are immediate children of this link.
std::optional< math::Pose3d > WorldInertialPose(const EntityComponentManager &_ecm) const
Get the world pose of the link inertia.
Component< bool, class WindModeTag > WindMode
A component used to indicate whether an entity is affected by wind.
Definition: gz/sim/components/WindMode.hh:33
void ResetEntity(gz::sim::Entity _newEntity)
Reset Entity to a new one.
std::optional< double > WorldKineticEnergy(const EntityComponentManager &_ecm) const
Get the rotational and translational kinetic energy of the link with respect to the world frame.
gz::sim::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.
Component< std::string, class NameTag > Name
This component holds an entity's name. The component has no concept of scoped names nor does it care ...
Definition: gz/sim/components/Name.hh:35
std::optional< math::Vector3d > WorldLinearAcceleration(const EntityComponentManager &_ecm) const
Get the linear acceleration of the body in the world frame.
const Entity kNullEntity
Indicates a non-existant or invalid Entity.
Definition: gz/sim/Entity.hh:62
void EnableAccelerationChecks(EntityComponentManager &_ecm, bool _enable=true) const
By default, Gazebo will not report accelerations for a link, so functions like WorldLinearAcceleratio...
std::vector< gz::sim::Entity > Visuals(const EntityComponentManager &_ecm) const
Get all visuals which are immediate children of this link.
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.
std::optional< math::Pose3d > WorldPose(const EntityComponentManager &_ecm) const
Get the pose of the link frame in the world coordinate frame.
std::vector< gz::sim::Entity > Collisions(const EntityComponentManager &_ecm) const
Get all collisions which are immediate children of this link.
uint64_t CollisionCount(const EntityComponentManager &_ecm) const
Get the number of collisions which are immediate children of this link.
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....
bool WindMode(const EntityComponentManager &_ecm) const
Get whether this link has wind enabled.
std::optional< math::Matrix3d > WorldInertiaMatrix(const EntityComponentManager &_ecm) const
Get the inertia matrix in the world frame.
gz::sim::Entity Entity() const
Get the entity which this Link is related to.
Component< NoData, class LinkTag > Link
A component that identifies an entity as being a link.
Definition: gz/sim/components/Link.hh:33
This class provides wrappers around entities and components which are more convenient and straight-fo...
Definition: gz/sim/Link.hh:63
bool Valid(const EntityComponentManager &_ecm) const
Check whether this link correctly refers to an entity that has a components::Link.
std::optional< math::Vector3d > WorldAngularVelocity(const EntityComponentManager &_ecm) const
Get the angular velocity of the link in the world frame.
bool IsCanonical(const EntityComponentManager &_ecm) const
Check if this is the canonical link.
std::optional< std::string > Name(const EntityComponentManager &_ecm) const
Get the link's unscoped name.
gz::sim::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.
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,...
void EnableVelocityChecks(EntityComponentManager &_ecm, bool _enable=true) const
By default, Gazebo will not report velocities for a link, so functions like WorldLinearVelocity will ...