Public Member Functions | List of all members
sdf::SDF_VERSION_NAMESPACE::Link Class Reference

#include <Link.hh>

Public Member Functions

 Link ()
 Default constructor. More...
 
bool AddCollision (const Collision &_collision)
 Add a collision to the link. More...
 
bool AddLight (const Light &_light)
 Add a light to the link. More...
 
bool AddParticleEmitter (const ParticleEmitter &_emitter)
 Add a particle emitter to the link. More...
 
bool AddProjector (const Projector &_projector)
 Add a projector to the link. More...
 
bool AddSensor (const Sensor &_sensor)
 Add a sensor to the link. More...
 
bool AddVisual (const Visual &_visual)
 Add a visual to the link. More...
 
bool AutoInertia () const
 Check if the automatic calculation for the link inertial is enabled or not. More...
 
sdf::ElementPtr AutoInertiaParams () const
 Get the ElementPtr to the <auto_inertia_params> element This element can be used as a parent element to hold user-defined params for the custom moment of inertia calculator. More...
 
bool AutoInertiaSaved () const
 Check if the inertial values for this link were saved. More...
 
void ClearCollisions ()
 Remove all collisions. More...
 
void ClearLights ()
 Remove all lights. More...
 
void ClearParticleEmitters ()
 Remove all particle emitters. More...
 
void ClearProjectors ()
 Remove all projectors. More...
 
void ClearSensors ()
 Remove all sensors. More...
 
void ClearVisuals ()
 Remove all visuals. More...
 
const CollisionCollisionByIndex (const uint64_t _index) const
 Get a collision based on an index. More...
 
CollisionCollisionByIndex (uint64_t _index)
 Get a mutable collision based on an index. More...
 
CollisionCollisionByName (const std::string &_name)
 Get a mutable collision based on a name. More...
 
const CollisionCollisionByName (const std::string &_name) const
 Get a collision based on a name. More...
 
uint64_t CollisionCount () const
 Get the number of collisions. More...
 
bool CollisionNameExists (const std::string &_name) const
 Get whether a collision name exists. More...
 
std::optional< double > Density () const
 Get the density of the inertial if it has been set. More...
 
sdf::ElementPtr Element () const
 Get a pointer to the SDF element that was used during load. More...
 
bool EnableGravity () const
 Check if this link should be subject to gravity. More...
 
bool EnableWind () const
 Check if this link should be subject to wind. More...
 
const gz::math::Inertiald & Inertial () const
 Get the inertial value for this link. More...
 
const LightLightByIndex (const uint64_t _index) const
 Get a light based on an index. More...
 
LightLightByIndex (uint64_t _index)
 Get a mutable light based on an index. More...
 
LightLightByName (const std::string &_name)
 Get a mutable light based on a name. More...
 
const LightLightByName (const std::string &_name) const
 Get a light based on a name. More...
 
uint64_t LightCount () const
 Get the number of lights. More...
 
bool LightNameExists (const std::string &_name) const
 Get whether a light name exists. More...
 
Errors Load (ElementPtr _sdf)
 Load the link based on a element pointer. More...
 
Errors Load (ElementPtr _sdf, const ParserConfig &_config)
 Load the link based on a element pointer. More...
 
std::string Name () const
 Get the name of the link. More...
 
const ParticleEmitterParticleEmitterByIndex (const uint64_t _index) const
 Get a particle emitter based on an index. More...
 
ParticleEmitterParticleEmitterByIndex (uint64_t _index)
 Get a mutable particle emitter based on an index. More...
 
ParticleEmitterParticleEmitterByName (const std::string &_name)
 Get a mutable particle emitter based on a name. More...
 
const ParticleEmitterParticleEmitterByName (const std::string &_name) const
 Get a particle emitter based on a name. More...
 
uint64_t ParticleEmitterCount () const
 Get the number of particle emitters. More...
 
bool ParticleEmitterNameExists (const std::string &_name) const
 Get whether a particle emitter name exists. More...
 
const std::string & PoseRelativeTo () const
 Get the name of the coordinate frame relative to which this object's pose is expressed. More...
 
const ProjectorProjectorByIndex (const uint64_t _index) const
 Get a projector based on an index. More...
 
ProjectorProjectorByIndex (uint64_t _index)
 Get a mutable projector based on an index. More...
 
ProjectorProjectorByName (const std::string &_name)
 Get a mutable projector based on a name. More...
 
const ProjectorProjectorByName (const std::string &_name) const
 Get a projector based on a name. More...
 
uint64_t ProjectorCount () const
 Get the number of projectors. More...
 
bool ProjectorNameExists (const std::string &_name) const
 Get whether a projector name exists. More...
 
const gz::math::Pose3d & RawPose () const
 Get the pose of the link. More...
 
void ResolveAutoInertials (sdf::Errors &_errors, const ParserConfig &_config)
 Calculate & set inertial values(mass, mass matrix & inertial pose) for the link. More...
 
Errors ResolveInertial (gz::math::Inertiald &_inertial, const std::string &_resolveTo="") const
 Resolve the Inertial to a specified frame. More...
 
sdf::SemanticPose SemanticPose () const
 Get SemanticPose object of this object to aid in resolving poses. More...
 
const SensorSensorByIndex (const uint64_t _index) const
 Get a sensor based on an index. More...
 
SensorSensorByIndex (uint64_t _index)
 Get a mutable sensor based on an index. More...
 
SensorSensorByName (const std::string &_name)
 Get a mutable sensor based on a name. More...
 
const SensorSensorByName (const std::string &_name) const
 Get a sensor based on a name. More...
 
uint64_t SensorCount () const
 Get the number of sensors. More...
 
bool SensorNameExists (const std::string &_name) const
 Get whether a sensor name exists. More...
 
void SetAutoInertia (bool _autoInertia)
 Enable automatic inertial calculations by setting autoInertia to true. More...
 
void SetAutoInertiaParams (const sdf::ElementPtr _autoInertiaParams)
 Function to set the auto inertia params using a sdf ElementPtr object. More...
 
void SetAutoInertiaSaved (bool _autoInertiaSaved)
 Set the autoInertiaSaved() values. More...
 
void SetDensity (double _density)
 Set the density of the inertial. More...
 
void SetEnableGravity (bool _enableGravity)
 Set whether this link should be subject to gravity. More...
 
void SetEnableWind (bool _enableWind)
 Set whether this link should be subject to wind. More...
 
bool SetInertial (const gz::math::Inertiald &_inertial)
 Set the inertial value for this link. More...
 
void SetName (const std::string &_name)
 Set the name of the link. More...
 
void SetPoseRelativeTo (const std::string &_frame)
 Set the name of the coordinate frame relative to which this object's pose is expressed. More...
 
void SetRawPose (const gz::math::Pose3d &_pose)
 Set the pose of the link. More...
 
sdf::ElementPtr ToElement () const
 Create and return an SDF element filled with data from this link. More...
 
const VisualVisualByIndex (const uint64_t _index) const
 Get a visual based on an index. More...
 
VisualVisualByIndex (uint64_t _index)
 Get a mutable visual based on an index. More...
 
VisualVisualByName (const std::string &_name)
 Get a mutable visual based on a name. More...
 
const VisualVisualByName (const std::string &_name) const
 Get a visual based on a name. More...
 
uint64_t VisualCount () const
 Get the number of visuals. More...
 
bool VisualNameExists (const std::string &_name) const
 Get whether a visual name exists. More...
 

Constructor & Destructor Documentation

◆ Link()

sdf::SDF_VERSION_NAMESPACE::Link::Link ( )

Default constructor.

Member Function Documentation

◆ AddCollision()

bool sdf::SDF_VERSION_NAMESPACE::Link::AddCollision ( const Collision _collision)

Add a collision to the link.

Parameters
[in]_collisionCollision to add.
Returns
True if successful, false if a collision with the name already exists.

◆ AddLight()

bool sdf::SDF_VERSION_NAMESPACE::Link::AddLight ( const Light _light)

Add a light to the link.

Parameters
[in]_lightLight to add.
Returns
True if successful, false if a light with the name already exists.

◆ AddParticleEmitter()

bool sdf::SDF_VERSION_NAMESPACE::Link::AddParticleEmitter ( const ParticleEmitter _emitter)

Add a particle emitter to the link.

Parameters
[in]_emitterParticle emitter to add.
Returns
True if successful, false if a particle emitter with the name already exists.

◆ AddProjector()

bool sdf::SDF_VERSION_NAMESPACE::Link::AddProjector ( const Projector _projector)

Add a projector to the link.

Parameters
[in]_projectorProjector to add.
Returns
True if successful, false if a projector with the name already exists.

◆ AddSensor()

bool sdf::SDF_VERSION_NAMESPACE::Link::AddSensor ( const Sensor _sensor)

Add a sensor to the link.

Parameters
[in]_sensorSensor to add.
Returns
True if successful, false if a sensor with the name already exists.

◆ AddVisual()

bool sdf::SDF_VERSION_NAMESPACE::Link::AddVisual ( const Visual _visual)

Add a visual to the link.

Parameters
[in]_visualVisual to add.
Returns
True if successful, false if a visual with the name already exists.

◆ AutoInertia()

bool sdf::SDF_VERSION_NAMESPACE::Link::AutoInertia ( ) const

Check if the automatic calculation for the link inertial is enabled or not.

Returns
True if automatic calculation is enabled. This can be done setting the auto attribute of the <inertial> element of the link to true or by setting the autoInertia member to true using SetAutoInertia().

◆ AutoInertiaParams()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Link::AutoInertiaParams ( ) const

Get the ElementPtr to the <auto_inertia_params> element This element can be used as a parent element to hold user-defined params for the custom moment of inertia calculator.

Returns
ElementPtr object for the <auto_inertia_params> element.

◆ AutoInertiaSaved()

bool sdf::SDF_VERSION_NAMESPACE::Link::AutoInertiaSaved ( ) const

Check if the inertial values for this link were saved.

If true, the inertial values for this link wont be calculated when CalculateInertial() is called. This value is set to true when CalculateInertial() is called with SAVE_CALCULATION configuration.

Returns
True if CalculateInertial() was called with SAVE_CALCULATION configuration, false otherwise.

◆ ClearCollisions()

void sdf::SDF_VERSION_NAMESPACE::Link::ClearCollisions ( )

Remove all collisions.

◆ ClearLights()

void sdf::SDF_VERSION_NAMESPACE::Link::ClearLights ( )

Remove all lights.

◆ ClearParticleEmitters()

void sdf::SDF_VERSION_NAMESPACE::Link::ClearParticleEmitters ( )

Remove all particle emitters.

◆ ClearProjectors()

void sdf::SDF_VERSION_NAMESPACE::Link::ClearProjectors ( )

Remove all projectors.

◆ ClearSensors()

void sdf::SDF_VERSION_NAMESPACE::Link::ClearSensors ( )

Remove all sensors.

◆ ClearVisuals()

void sdf::SDF_VERSION_NAMESPACE::Link::ClearVisuals ( )

Remove all visuals.

◆ CollisionByIndex() [1/2]

const Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByIndex ( const uint64_t  _index) const

Get a collision based on an index.

Parameters
[in]_indexIndex of the collision. The index should be in the range [0..CollisionCount()).
Returns
Pointer to the collision. Nullptr if the index does not exist.
See also
uint64_t CollisionCount() const

◆ CollisionByIndex() [2/2]

Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByIndex ( uint64_t  _index)

Get a mutable collision based on an index.

Parameters
[in]_indexIndex of the collision. The index should be in the range [0..CollisionCount()).
Returns
Pointer to the collision. Nullptr if the index does not exist.
See also
uint64_t CollisionCount() const

◆ CollisionByName() [1/2]

Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByName ( const std::string &  _name)

Get a mutable collision based on a name.

Parameters
[in]_nameName of the collision.
Returns
Pointer to the collision. Nullptr if the name does not exist.

◆ CollisionByName() [2/2]

const Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByName ( const std::string &  _name) const

Get a collision based on a name.

Parameters
[in]_nameName of the collision.
Returns
Pointer to the collision. Nullptr if the name does not exist.

◆ CollisionCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Link::CollisionCount ( ) const

Get the number of collisions.

Returns
Number of collisions contained in this Link object.

◆ CollisionNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Link::CollisionNameExists ( const std::string &  _name) const

Get whether a collision name exists.

Parameters
[in]_nameName of the collision to check.
Returns
True if there exists a collision with the given name.

◆ Density()

std::optional<double> sdf::SDF_VERSION_NAMESPACE::Link::Density ( ) const

Get the density of the inertial if it has been set.

Returns
Density of the inertial if it has been set, otherwise std::nullopt.

◆ Element()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Link::Element ( ) const

Get a pointer to the SDF element that was used during load.

Returns
SDF element pointer. The value will be nullptr if Load has not been called.

◆ EnableGravity()

bool sdf::SDF_VERSION_NAMESPACE::Link::EnableGravity ( ) const

Check if this link should be subject to gravity.

If true, this link should be affected by gravity.

Returns
true if the model should be subject to gravity, false otherwise.

◆ EnableWind()

bool sdf::SDF_VERSION_NAMESPACE::Link::EnableWind ( ) const

Check if this link should be subject to wind.

If true, this link should be affected by wind.

Returns
true if the model should be subject to wind, false otherwise.
See also
bool Model::EnableWind

◆ Inertial()

const gz::math::Inertiald& sdf::SDF_VERSION_NAMESPACE::Link::Inertial ( ) const

Get the inertial value for this link.

The inertial object consists of the link's mass, a 3x3 rotational inertia matrix, and a pose for the inertial reference frame. The units for mass is kilograms with a default value of 1kg. The 3x3 rotational inertia matrix is symmetric and only 6 above-diagonal elements of this matrix are specified the Interial's gz::math::MassMatrix3 property.

The origin of the inertial reference frame needs to be at the center of mass expressed in this link's frame. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.

Returns
The link's inertial value.
See also
void SetInertial(const gz::math::Inertiald &_inertial)

◆ LightByIndex() [1/2]

const Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByIndex ( const uint64_t  _index) const

Get a light based on an index.

Parameters
[in]_indexIndex of the light. The index should be in the range [0..LightCount()).
Returns
Pointer to the light. Nullptr if the index does not exist.
See also
uint64_t LightCount() const

◆ LightByIndex() [2/2]

Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByIndex ( uint64_t  _index)

Get a mutable light based on an index.

Parameters
[in]_indexIndex of the light. The index should be in the range [0..LightCount()).
Returns
Pointer to the light. Nullptr if the index does not exist.
See also
uint64_t LightCount() const

◆ LightByName() [1/2]

Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByName ( const std::string &  _name)

Get a mutable light based on a name.

Parameters
[in]_nameName of the light.
Returns
Pointer to the light. Nullptr if the name does not exist.

◆ LightByName() [2/2]

const Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByName ( const std::string &  _name) const

Get a light based on a name.

Parameters
[in]_nameName of the light.
Returns
Pointer to the light. Nullptr if the name does not exist.

◆ LightCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Link::LightCount ( ) const

Get the number of lights.

Returns
Number of lights contained in this Link object.

◆ LightNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Link::LightNameExists ( const std::string &  _name) const

Get whether a light name exists.

Parameters
[in]_nameName of the light to check.
Returns
True if there exists a light with the given name.

◆ Load() [1/2]

Errors sdf::SDF_VERSION_NAMESPACE::Link::Load ( ElementPtr  _sdf)

Load the link based on a element pointer.

This is not the usual entry point. Typical usage of the SDF DOM is through the Root object.

Parameters
[in]_sdfThe SDF Element pointer
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Load() [2/2]

Errors sdf::SDF_VERSION_NAMESPACE::Link::Load ( ElementPtr  _sdf,
const ParserConfig _config 
)

Load the link based on a element pointer.

This is not the usual entry point. Typical usage of the SDF DOM is through the Root object.

Parameters
[in]_sdfThe SDF Element pointer
[in]_configParser configuration
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Name()

std::string sdf::SDF_VERSION_NAMESPACE::Link::Name ( ) const

Get the name of the link.

The name of a link must be unique within the scope of a Model.

Returns
Name of the link.

◆ ParticleEmitterByIndex() [1/2]

const ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByIndex ( const uint64_t  _index) const

Get a particle emitter based on an index.

Parameters
[in]_indexIndex of the particle emitter. The index should be in the range [0..ParticleEmitterCount()).
Returns
Pointer to the particle emitter. Nullptr if the index does not exist.
See also
uint64_t ParticleEmitterCount() const

◆ ParticleEmitterByIndex() [2/2]

ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByIndex ( uint64_t  _index)

Get a mutable particle emitter based on an index.

Parameters
[in]_indexIndex of the particle emitter. The index should be in the range [0..ParticleEmitterCount()).
Returns
Pointer to the particle emitter. Nullptr if the index does not exist.
See also
uint64_t ParticleEmitterCount() const

◆ ParticleEmitterByName() [1/2]

ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByName ( const std::string &  _name)

Get a mutable particle emitter based on a name.

Parameters
[in]_nameName of the particle emitter.
Returns
Pointer to the particle emitter. Nullptr if a particle emitter with the given name does not exist.
See also
bool ParticleEmitterNameExists(const std::string &_name) const

◆ ParticleEmitterByName() [2/2]

const ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByName ( const std::string &  _name) const

Get a particle emitter based on a name.

Parameters
[in]_nameName of the particle emitter.
Returns
Pointer to the particle emitter. Nullptr if a particle emitter with the given name does not exist.
See also
bool ParticleEmitterNameExists(const std::string &_name) const

◆ ParticleEmitterCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterCount ( ) const

Get the number of particle emitters.

Returns
Number of particle emitters contained in this Link object.

◆ ParticleEmitterNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterNameExists ( const std::string &  _name) const

Get whether a particle emitter name exists.

Parameters
[in]_nameName of the particle emitter to check.
Returns
True if there exists a particle emitter with the given name.

◆ PoseRelativeTo()

const std::string& sdf::SDF_VERSION_NAMESPACE::Link::PoseRelativeTo ( ) const

Get the name of the coordinate frame relative to which this object's pose is expressed.

An empty value indicates that the frame is relative to the parent model.

Returns
The name of the pose relative-to frame.

◆ ProjectorByIndex() [1/2]

const Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByIndex ( const uint64_t  _index) const

Get a projector based on an index.

Parameters
[in]_indexIndex of the projector. The index should be in the range [0..ProjectorCount()).
Returns
Pointer to the projector. Nullptr if the index does not exist.
See also
uint64_t ProjectorCount() const

◆ ProjectorByIndex() [2/2]

Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByIndex ( uint64_t  _index)

Get a mutable projector based on an index.

Parameters
[in]_indexIndex of the projector. The index should be in the range [0..ProjectorCount()).
Returns
Pointer to the projector. Nullptr if the index does not exist.
See also
uint64_t ProjectorCount() const

◆ ProjectorByName() [1/2]

Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByName ( const std::string &  _name)

Get a mutable projector based on a name.

Parameters
[in]_nameName of the projector.
Returns
Pointer to the projector. Nullptr if a projector with the given name does not exist.
See also
bool ProjectorNameExists(const std::string &_name) const

◆ ProjectorByName() [2/2]

const Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByName ( const std::string &  _name) const

Get a projector based on a name.

Parameters
[in]_nameName of the projector.
Returns
Pointer to the projector. Nullptr if a projector with the given name does not exist.
See also
bool ProjectorNameExists(const std::string &_name) const

◆ ProjectorCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Link::ProjectorCount ( ) const

Get the number of projectors.

Returns
Number of projectors contained in this Link object.

◆ ProjectorNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Link::ProjectorNameExists ( const std::string &  _name) const

Get whether a projector name exists.

Parameters
[in]_nameName of the projector to check.
Returns
True if there exists a projector with the given name.

◆ RawPose()

const gz::math::Pose3d& sdf::SDF_VERSION_NAMESPACE::Link::RawPose ( ) const

Get the pose of the link.

This is the pose of the link as specified in SDF (<link> <pose> ... </pose></link>).

Returns
The pose of the link.

◆ ResolveAutoInertials()

void sdf::SDF_VERSION_NAMESPACE::Link::ResolveAutoInertials ( sdf::Errors _errors,
const ParserConfig _config 
)

Calculate & set inertial values(mass, mass matrix & inertial pose) for the link.

Inertial values can be provided by the user through the SDF or can be calculated automatically by setting the auto attribute to true.

Parameters
[out]_errorsA vector of Errors object. Each object would contain an error code and an error message.
[in]_configCustom parser configuration

◆ ResolveInertial()

Errors sdf::SDF_VERSION_NAMESPACE::Link::ResolveInertial ( gz::math::Inertiald &  _inertial,
const std::string &  _resolveTo = "" 
) const

Resolve the Inertial to a specified frame.

If there are any errors resolving the Inertial, the output will not be modified.

Parameters
[out]_inertialThe resolved Inertial.
[in]_resolveToThe Inertial will be resolved with respect to this frame. If unset or empty, the default resolve-to frame will be used.
Returns
Errors in resolving pose.

◆ SemanticPose()

sdf::SemanticPose sdf::SDF_VERSION_NAMESPACE::Link::SemanticPose ( ) const

Get SemanticPose object of this object to aid in resolving poses.

Returns
SemanticPose object for this link.

◆ SensorByIndex() [1/2]

const Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByIndex ( const uint64_t  _index) const

Get a sensor based on an index.

Parameters
[in]_indexIndex of the sensor. The index should be in the range [0..SensorCount()).
Returns
Pointer to the sensor. Nullptr if the index does not exist.
See also
uint64_t SensorCount() const

◆ SensorByIndex() [2/2]

Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByIndex ( uint64_t  _index)

Get a mutable sensor based on an index.

Parameters
[in]_indexIndex of the sensor. The index should be in the range [0..SensorCount()).
Returns
Pointer to the sensor. Nullptr if the index does not exist.
See also
uint64_t SensorCount() const

◆ SensorByName() [1/2]

Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByName ( const std::string &  _name)

Get a mutable sensor based on a name.

Parameters
[in]_nameName of the sensor.
Returns
Pointer to the sensor. Nullptr if a sensor with the given name does not exist.
See also
bool SensorNameExists(const std::string &_name) const

◆ SensorByName() [2/2]

const Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByName ( const std::string &  _name) const

Get a sensor based on a name.

Parameters
[in]_nameName of the sensor.
Returns
Pointer to the sensor. Nullptr if a sensor with the given name does not exist.
See also
bool SensorNameExists(const std::string &_name) const

◆ SensorCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Link::SensorCount ( ) const

Get the number of sensors.

Returns
Number of sensors contained in this Link object.

◆ SensorNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Link::SensorNameExists ( const std::string &  _name) const

Get whether a sensor name exists.

Parameters
[in]_nameName of the sensor to check.
Returns
True if there exists a sensor with the given name.

◆ SetAutoInertia()

void sdf::SDF_VERSION_NAMESPACE::Link::SetAutoInertia ( bool  _autoInertia)

Enable automatic inertial calculations by setting autoInertia to true.

Parameters
[in]_autoInertiaTrue or False

◆ SetAutoInertiaParams()

void sdf::SDF_VERSION_NAMESPACE::Link::SetAutoInertiaParams ( const sdf::ElementPtr  _autoInertiaParams)

Function to set the auto inertia params using a sdf ElementPtr object.

Parameters
[in]_autoInertiaParamsElementPtr to <auto_inertia_params> element

◆ SetAutoInertiaSaved()

void sdf::SDF_VERSION_NAMESPACE::Link::SetAutoInertiaSaved ( bool  _autoInertiaSaved)

Set the autoInertiaSaved() values.

Parameters
[in]_autoInertiaSavedTrue or False

◆ SetDensity()

void sdf::SDF_VERSION_NAMESPACE::Link::SetDensity ( double  _density)

Set the density of the inertial.

Parameters
[in]_densityDensity of the inertial.

◆ SetEnableGravity()

void sdf::SDF_VERSION_NAMESPACE::Link::SetEnableGravity ( bool  _enableGravity)

Set whether this link should be subject to gravity.

Parameters
[in]_enableGravityTrue or false depending on whether the link should be subject to gravity.

◆ SetEnableWind()

void sdf::SDF_VERSION_NAMESPACE::Link::SetEnableWind ( bool  _enableWind)

Set whether this link should be subject to wind.

Parameters
[in]_enableWindTrue or false depending on whether the link should be subject to wind.
See also
Model::SetEnableWind(bool)

◆ SetInertial()

bool sdf::SDF_VERSION_NAMESPACE::Link::SetInertial ( const gz::math::Inertiald &  _inertial)

Set the inertial value for this link.

Parameters
[in]_inertialThe link's inertial value.
Returns
True if the inertial is valid, false otherwise.
See also
const gz::math::Inertiald &Inertial() const

◆ SetName()

void sdf::SDF_VERSION_NAMESPACE::Link::SetName ( const std::string &  _name)

Set the name of the link.

The name of a link must be unique within the scope of a Model.

Parameters
[in]_nameName of the link.

◆ SetPoseRelativeTo()

void sdf::SDF_VERSION_NAMESPACE::Link::SetPoseRelativeTo ( const std::string &  _frame)

Set the name of the coordinate frame relative to which this object's pose is expressed.

An empty value indicates that the frame is relative to the parent model.

Parameters
[in]_frameThe name of the pose relative-to frame.

◆ SetRawPose()

void sdf::SDF_VERSION_NAMESPACE::Link::SetRawPose ( const gz::math::Pose3d &  _pose)

Set the pose of the link.

See also
const gz::math::Pose3d &RawPose() const
Parameters
[in]_poseThe new link pose.

◆ ToElement()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Link::ToElement ( ) const

Create and return an SDF element filled with data from this link.

Note that parameter passing functionality is not captured with this function.

Returns
SDF element pointer with updated link values.

◆ VisualByIndex() [1/2]

const Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByIndex ( const uint64_t  _index) const

Get a visual based on an index.

Parameters
[in]_indexIndex of the visual. The index should be in the range [0..VisualCount()).
Returns
Pointer to the visual. Nullptr if the index does not exist.
See also
uint64_t VisualCount() const

◆ VisualByIndex() [2/2]

Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByIndex ( uint64_t  _index)

Get a mutable visual based on an index.

Parameters
[in]_indexIndex of the visual. The index should be in the range [0..VisualCount()).
Returns
Pointer to the visual. Nullptr if the index does not exist.
See also
uint64_t VisualCount() const

◆ VisualByName() [1/2]

Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByName ( const std::string &  _name)

Get a mutable visual based on a name.

Parameters
[in]_nameName of the visual.
Returns
Pointer to the visual. Nullptr if the name does not exist.

◆ VisualByName() [2/2]

const Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByName ( const std::string &  _name) const

Get a visual based on a name.

Parameters
[in]_nameName of the visual.
Returns
Pointer to the visual. Nullptr if the name does not exist.

◆ VisualCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Link::VisualCount ( ) const

Get the number of visuals.

Returns
Number of visuals contained in this Link object.

◆ VisualNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Link::VisualNameExists ( const std::string &  _name) const

Get whether a visual name exists.

Parameters
[in]_nameName of the visual to check.
Returns
True if there exists a visual with the given name.

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