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

#include <Link.hh>

Public Member Functions

 Link ()
 Default constructor. More...
 
 Link (const Link &_link)
 Copy constructor. More...
 
 Link (Link &&_link) noexcept
 Move constructor. More...
 
 ~Link ()
 Destructor. More...
 
const CollisionCollisionByIndex (const uint64_t _index) const
 Get a collision based on an index. 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...
 
sdf::ElementPtr Element () const
 Get a pointer to the SDF element that was used during load. 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...
 
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...
 
std::string Name () const
 Get the name of the link. More...
 
Linkoperator= (const Link &_link)
 Copy assignment operator. More...
 
Linkoperator= (Link &&_link)
 Move assignment operator. More...
 
const gz::math::Pose3d & Pose () const SDF_DEPRECATED(9.0)
 Get the pose of the link. More...
 
const std::string & PoseFrame () const SDF_DEPRECATED(9.0)
 Get the name of the coordinate frame in which this link's pose is expressed. More...
 
const std::string & PoseRelativeTo () const
 Get the name of the coordinate frame relative to which this object's pose is expressed. More...
 
const gz::math::Pose3d & RawPose () const
 Get the pose of 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...
 
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 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) const
 Set the name of the link. More...
 
void SetPose (const gz::math::Pose3d &_pose) SDF_DEPRECATED(9.0)
 Set the pose of the link. More...
 
void SetPoseFrame (const std::string &_frame) SDF_DEPRECATED(9.0)
 Set the name of the coordinate frame in which this link's pose is expressed. 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...
 
const VisualVisualByIndex (const uint64_t _index) const
 Get a visual based on an index. 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() [1/3]

sdf::v9::Link::Link ( )

Default constructor.

◆ Link() [2/3]

sdf::v9::Link::Link ( const Link _link)

Copy constructor.

Parameters
[in]_linkLink to copy.

◆ Link() [3/3]

sdf::v9::Link::Link ( Link &&  _link)
noexcept

Move constructor.

Parameters
[in]_linkLink to move.

◆ ~Link()

sdf::v9::Link::~Link ( )

Destructor.

Member Function Documentation

◆ CollisionByIndex()

const Collision* sdf::v9::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

◆ CollisionByName()

const Collision* sdf::v9::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::v9::Link::CollisionCount ( ) const

Get the number of collisions.

Returns
Number of collisions contained in this Link object.

◆ CollisionNameExists()

bool sdf::v9::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.

◆ Element()

sdf::ElementPtr sdf::v9::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.

◆ EnableWind()

bool sdf::v9::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::v9::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()

const Light* sdf::v9::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

◆ LightByName()

const Light* sdf::v9::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::v9::Link::LightCount ( ) const

Get the number of lights.

Returns
Number of lights contained in this Link object.

◆ LightNameExists()

bool sdf::v9::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()

Errors sdf::v9::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.

◆ Name()

std::string sdf::v9::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.

◆ operator=() [1/2]

Link& sdf::v9::Link::operator= ( const Link _link)

Copy assignment operator.

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

◆ operator=() [2/2]

Link& sdf::v9::Link::operator= ( Link &&  _link)

Move assignment operator.

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

◆ Pose()

const gz::math::Pose3d& sdf::v9::Link::Pose ( ) 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.
Deprecated:
See RawPose.

◆ PoseFrame()

const std::string& sdf::v9::Link::PoseFrame ( ) const

Get the name of the coordinate frame in which this link's pose is expressed.

A empty value indicates that the frame is the parent model.

Returns
The name of the pose frame.
Deprecated:
See PoseRelativeTo.

◆ PoseRelativeTo()

const std::string& sdf::v9::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.

◆ RawPose()

const gz::math::Pose3d& sdf::v9::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.

◆ ResolveInertial()

Errors sdf::v9::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::v9::Link::SemanticPose ( ) const

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

Returns
SemanticPose object for this link.

◆ SensorByIndex()

const Sensor* sdf::v9::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

◆ SensorByName()

const Sensor* sdf::v9::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::v9::Link::SensorCount ( ) const

Get the number of sensors.

Returns
Number of sensors contained in this Link object.

◆ SensorNameExists()

bool sdf::v9::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.

◆ SetEnableWind()

void sdf::v9::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::v9::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::v9::Link::SetName ( const std::string &  _name) const

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.

◆ SetPose()

void sdf::v9::Link::SetPose ( const gz::math::Pose3d &  _pose)

Set the pose of the link.

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

◆ SetPoseFrame()

void sdf::v9::Link::SetPoseFrame ( const std::string &  _frame)

Set the name of the coordinate frame in which this link's pose is expressed.

A empty value indicates that the frame is the parent model.

Parameters
[in]_frameThe name of the pose frame.
Deprecated:
See SetPoseRelativeTo.

◆ SetPoseRelativeTo()

void sdf::v9::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::v9::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.

◆ VisualByIndex()

const Visual* sdf::v9::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

◆ VisualByName()

const Visual* sdf::v9::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::v9::Link::VisualCount ( ) const

Get the number of visuals.

Returns
Number of visuals contained in this Link object.

◆ VisualNameExists()

bool sdf::v9::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: