#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... | |
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 Collision * | CollisionByIndex (const uint64_t _index) const |
Get a collision based on an index. More... | |
Collision * | CollisionByIndex (uint64_t _index) |
Get a mutable collision based on an index. More... | |
Collision * | CollisionByName (const std::string &_name) |
Get a mutable collision based on a name. More... | |
const Collision * | CollisionByName (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 | 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 Light * | LightByIndex (const uint64_t _index) const |
Get a light based on an index. More... | |
Light * | LightByIndex (uint64_t _index) |
Get a mutable light based on an index. More... | |
Light * | LightByName (const std::string &_name) |
Get a mutable light based on a name. More... | |
const Light * | LightByName (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 ParticleEmitter * | ParticleEmitterByIndex (const uint64_t _index) const |
Get a particle emitter based on an index. More... | |
ParticleEmitter * | ParticleEmitterByIndex (uint64_t _index) |
Get a mutable particle emitter based on an index. More... | |
ParticleEmitter * | ParticleEmitterByName (const std::string &_name) |
Get a mutable particle emitter based on a name. More... | |
const ParticleEmitter * | ParticleEmitterByName (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 Projector * | ProjectorByIndex (const uint64_t _index) const |
Get a projector based on an index. More... | |
Projector * | ProjectorByIndex (uint64_t _index) |
Get a mutable projector based on an index. More... | |
Projector * | ProjectorByName (const std::string &_name) |
Get a mutable projector based on a name. More... | |
const Projector * | ProjectorByName (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... | |
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 Sensor * | SensorByIndex (const uint64_t _index) const |
Get a sensor based on an index. More... | |
Sensor * | SensorByIndex (uint64_t _index) |
Get a mutable sensor based on an index. More... | |
Sensor * | SensorByName (const std::string &_name) |
Get a mutable sensor based on a name. More... | |
const Sensor * | SensorByName (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 | 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 Visual * | VisualByIndex (const uint64_t _index) const |
Get a visual based on an index. More... | |
Visual * | VisualByIndex (uint64_t _index) |
Get a mutable visual based on an index. More... | |
Visual * | VisualByName (const std::string &_name) |
Get a mutable visual based on a name. More... | |
const Visual * | VisualByName (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... | |
sdf::SDF_VERSION_NAMESPACE::Link::Link | ( | ) |
Default constructor.
bool sdf::SDF_VERSION_NAMESPACE::Link::AddCollision | ( | const Collision & | _collision | ) |
Add a collision to the link.
[in] | _collision | Collision to add. |
bool sdf::SDF_VERSION_NAMESPACE::Link::AddLight | ( | const Light & | _light | ) |
Add a light to the link.
[in] | _light | Light to add. |
bool sdf::SDF_VERSION_NAMESPACE::Link::AddParticleEmitter | ( | const ParticleEmitter & | _emitter | ) |
Add a particle emitter to the link.
[in] | _emitter | Particle emitter to add. |
bool sdf::SDF_VERSION_NAMESPACE::Link::AddProjector | ( | const Projector & | _projector | ) |
Add a projector to the link.
[in] | _projector | Projector to add. |
bool sdf::SDF_VERSION_NAMESPACE::Link::AddSensor | ( | const Sensor & | _sensor | ) |
Add a sensor to the link.
[in] | _sensor | Sensor to add. |
bool sdf::SDF_VERSION_NAMESPACE::Link::AddVisual | ( | const Visual & | _visual | ) |
Add a visual to the link.
[in] | _visual | Visual to add. |
void sdf::SDF_VERSION_NAMESPACE::Link::ClearCollisions | ( | ) |
Remove all collisions.
void sdf::SDF_VERSION_NAMESPACE::Link::ClearLights | ( | ) |
Remove all lights.
void sdf::SDF_VERSION_NAMESPACE::Link::ClearParticleEmitters | ( | ) |
Remove all particle emitters.
void sdf::SDF_VERSION_NAMESPACE::Link::ClearProjectors | ( | ) |
Remove all projectors.
void sdf::SDF_VERSION_NAMESPACE::Link::ClearSensors | ( | ) |
Remove all sensors.
void sdf::SDF_VERSION_NAMESPACE::Link::ClearVisuals | ( | ) |
Remove all visuals.
const Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByIndex | ( | const uint64_t | _index | ) | const |
Get a collision based on an index.
[in] | _index | Index of the collision. The index should be in the range [0..CollisionCount()). |
Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByIndex | ( | uint64_t | _index | ) |
Get a mutable collision based on an index.
[in] | _index | Index of the collision. The index should be in the range [0..CollisionCount()). |
Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByName | ( | const std::string & | _name | ) |
Get a mutable collision based on a name.
[in] | _name | Name of the collision. |
const Collision* sdf::SDF_VERSION_NAMESPACE::Link::CollisionByName | ( | const std::string & | _name | ) | const |
Get a collision based on a name.
[in] | _name | Name of the collision. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Link::CollisionCount | ( | ) | const |
Get the number of collisions.
bool sdf::SDF_VERSION_NAMESPACE::Link::CollisionNameExists | ( | const std::string & | _name | ) | const |
Get whether a collision name exists.
[in] | _name | Name of the collision to check. |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Link::Element | ( | ) | const |
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.
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.
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.
const Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByIndex | ( | const uint64_t | _index | ) | const |
Get a light based on an index.
[in] | _index | Index of the light. The index should be in the range [0..LightCount()). |
Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByIndex | ( | uint64_t | _index | ) |
Get a mutable light based on an index.
[in] | _index | Index of the light. The index should be in the range [0..LightCount()). |
Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByName | ( | const std::string & | _name | ) |
Get a mutable light based on a name.
[in] | _name | Name of the light. |
const Light* sdf::SDF_VERSION_NAMESPACE::Link::LightByName | ( | const std::string & | _name | ) | const |
Get a light based on a name.
[in] | _name | Name of the light. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Link::LightCount | ( | ) | const |
Get the number of lights.
bool sdf::SDF_VERSION_NAMESPACE::Link::LightNameExists | ( | const std::string & | _name | ) | const |
Get whether a light name exists.
[in] | _name | Name of the light to check. |
Errors sdf::SDF_VERSION_NAMESPACE::Link::Load | ( | ElementPtr | _sdf | ) |
Errors sdf::SDF_VERSION_NAMESPACE::Link::Load | ( | ElementPtr | _sdf, |
const ParserConfig & | _config | ||
) |
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.
const ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByIndex | ( | const uint64_t | _index | ) | const |
Get a particle emitter based on an index.
[in] | _index | Index of the particle emitter. The index should be in the range [0..ParticleEmitterCount()). |
ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByIndex | ( | uint64_t | _index | ) |
Get a mutable particle emitter based on an index.
[in] | _index | Index of the particle emitter. The index should be in the range [0..ParticleEmitterCount()). |
ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByName | ( | const std::string & | _name | ) |
Get a mutable particle emitter based on a name.
[in] | _name | Name of the particle emitter. |
const ParticleEmitter* sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterByName | ( | const std::string & | _name | ) | const |
Get a particle emitter based on a name.
[in] | _name | Name of the particle emitter. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterCount | ( | ) | const |
Get the number of particle emitters.
bool sdf::SDF_VERSION_NAMESPACE::Link::ParticleEmitterNameExists | ( | const std::string & | _name | ) | const |
Get whether a particle emitter name exists.
[in] | _name | Name of the particle emitter to check. |
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.
const Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByIndex | ( | const uint64_t | _index | ) | const |
Get a projector based on an index.
[in] | _index | Index of the projector. The index should be in the range [0..ProjectorCount()). |
Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByIndex | ( | uint64_t | _index | ) |
Get a mutable projector based on an index.
[in] | _index | Index of the projector. The index should be in the range [0..ProjectorCount()). |
Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByName | ( | const std::string & | _name | ) |
Get a mutable projector based on a name.
[in] | _name | Name of the projector. |
const Projector* sdf::SDF_VERSION_NAMESPACE::Link::ProjectorByName | ( | const std::string & | _name | ) | const |
Get a projector based on a name.
[in] | _name | Name of the projector. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Link::ProjectorCount | ( | ) | const |
Get the number of projectors.
bool sdf::SDF_VERSION_NAMESPACE::Link::ProjectorNameExists | ( | const std::string & | _name | ) | const |
Get whether a projector name exists.
[in] | _name | Name of the projector to check. |
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>).
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.
[out] | _inertial | The resolved Inertial. |
[in] | _resolveTo | The Inertial will be resolved with respect to this frame. If unset or empty, the default resolve-to frame will be used. |
sdf::SemanticPose sdf::SDF_VERSION_NAMESPACE::Link::SemanticPose | ( | ) | const |
Get SemanticPose object of this object to aid in resolving poses.
const Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByIndex | ( | const uint64_t | _index | ) | const |
Get a sensor based on an index.
[in] | _index | Index of the sensor. The index should be in the range [0..SensorCount()). |
Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByIndex | ( | uint64_t | _index | ) |
Get a mutable sensor based on an index.
[in] | _index | Index of the sensor. The index should be in the range [0..SensorCount()). |
Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByName | ( | const std::string & | _name | ) |
Get a mutable sensor based on a name.
[in] | _name | Name of the sensor. |
const Sensor* sdf::SDF_VERSION_NAMESPACE::Link::SensorByName | ( | const std::string & | _name | ) | const |
Get a sensor based on a name.
[in] | _name | Name of the sensor. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Link::SensorCount | ( | ) | const |
Get the number of sensors.
bool sdf::SDF_VERSION_NAMESPACE::Link::SensorNameExists | ( | const std::string & | _name | ) | const |
Get whether a sensor name exists.
[in] | _name | Name of the sensor to check. |
void sdf::SDF_VERSION_NAMESPACE::Link::SetEnableGravity | ( | bool | _enableGravity | ) |
Set whether this link should be subject to gravity.
[in] | _enableGravity | True or false depending on whether the link should be subject to gravity. |
void sdf::SDF_VERSION_NAMESPACE::Link::SetEnableWind | ( | bool | _enableWind | ) |
Set whether this link should be subject to wind.
[in] | _enableWind | True or false depending on whether the link should be subject to wind. |
bool sdf::SDF_VERSION_NAMESPACE::Link::SetInertial | ( | const gz::math::Inertiald & | _inertial | ) |
Set the inertial value for this link.
[in] | _inertial | The link's inertial value. |
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.
[in] | _name | Name of the link. |
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.
[in] | _frame | The name of the pose relative-to frame. |
void sdf::SDF_VERSION_NAMESPACE::Link::SetRawPose | ( | const gz::math::Pose3d & | _pose | ) |
Set the pose of the link.
[in] | _pose | The new link pose. |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Link::ToElement | ( | ) | const |
const Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByIndex | ( | const uint64_t | _index | ) | const |
Get a visual based on an index.
[in] | _index | Index of the visual. The index should be in the range [0..VisualCount()). |
Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByIndex | ( | uint64_t | _index | ) |
Get a mutable visual based on an index.
[in] | _index | Index of the visual. The index should be in the range [0..VisualCount()). |
Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByName | ( | const std::string & | _name | ) |
Get a mutable visual based on a name.
[in] | _name | Name of the visual. |
const Visual* sdf::SDF_VERSION_NAMESPACE::Link::VisualByName | ( | const std::string & | _name | ) | const |
Get a visual based on a name.
[in] | _name | Name of the visual. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Link::VisualCount | ( | ) | const |
Get the number of visuals.
bool sdf::SDF_VERSION_NAMESPACE::Link::VisualNameExists | ( | const std::string & | _name | ) | const |
Get whether a visual name exists.
[in] | _name | Name of the visual to check. |