23 #include <gz/math/Inertial.hh>
24 #include <gz/math/Pose3.hh>
25 #include <gz/utils/ImplPtr.hh>
37 inline namespace SDF_VERSION_NAMESPACE {
44 class ParticleEmitter;
48 struct PoseRelativeToGraph;
49 template <
typename T>
class ScopedGraph;
76 public: std::string
Name()
const;
81 public:
void SetName(
const std::string &_name);
86 public: std::optional<double>
Density()
const;
251 const uint64_t _index)
const;
272 const std::string &_name)
const;
292 const uint64_t _index)
const;
313 const std::string &_name)
const;
335 public:
const gz::math::Inertiald &
Inertial()
const;
351 const std::string &_resolveTo =
"")
const;
366 public:
const gz::math::Pose3d &
RawPose()
const;
399 private:
void SetPoseRelativeToGraph(
515 GZ_UTILS_IMPL_PTR(dataPtr)
A collision element descibes the collision properties associated with a link.
Definition: Collision.hh:51
Provides a description of a light source.
Definition: Light.hh:64
const std::string & PoseRelativeTo() const
Get the name of the coordinate frame relative to which this object's pose is expressed.
Errors Load(ElementPtr _sdf, const ParserConfig &_config)
Load the link based on a element pointer.
std::string Name() const
Get the name of the link.
Errors Load(ElementPtr _sdf)
Load the link based on a element pointer.
void SetEnableWind(bool _enableWind)
Set whether this link should be subject to wind.
sdf::ElementPtr ToElement() const
Create and return an SDF element filled with data from this link.
void SetAutoInertiaParams(const sdf::ElementPtr _autoInertiaParams)
Function to set the auto inertia params using a sdf ElementPtr object.
void SetPoseRelativeTo(const std::string &_frame)
Set the name of the coordinate frame relative to which this object's pose is expressed.
ParticleEmitter * ParticleEmitterByIndex(uint64_t _index)
Get a mutable particle emitter based on an index.
const Collision * CollisionByIndex(const uint64_t _index) const
Get a collision based on an index.
const ParticleEmitter * ParticleEmitterByName(const std::string &_name) const
Get a particle emitter based on a name.
Visual * VisualByName(const std::string &_name)
Get a mutable visual based on a name.
const Light * LightByName(const std::string &_name) const
Get a light based on a name.
uint64_t ParticleEmitterCount() const
Get the number of particle emitters.
uint64_t VisualCount() const
Get the number of visuals.
Light * LightByName(const std::string &_name)
Get a mutable light based on a name.
std::optional< double > Density() const
Get the density of the inertial if it has been set.
const ParticleEmitter * ParticleEmitterByIndex(const uint64_t _index) const
Get a particle emitter based on an index.
const Visual * VisualByName(const std::string &_name) const
Get a visual based on a name.
void ClearSensors()
Remove all sensors.
uint64_t LightCount() const
Get the number of lights.
void ResolveAutoInertials(sdf::Errors &_errors, const ParserConfig &_config)
Calculate & set inertial values(mass, mass matrix & inertial pose) for the link.
const gz::math::Pose3d & RawPose() const
Get the pose of the link.
void ClearVisuals()
Remove all visuals.
const Light * LightByIndex(const uint64_t _index) const
Get a light based on an index.
Projector * ProjectorByIndex(uint64_t _index)
Get a mutable projector based on an index.
Collision * CollisionByIndex(uint64_t _index)
Get a mutable collision based on an index.
bool AddCollision(const Collision &_collision)
Add a collision to the link.
bool SetInertial(const gz::math::Inertiald &_inertial)
Set the inertial value for this link.
uint64_t CollisionCount() const
Get the number of collisions.
void ClearProjectors()
Remove all projectors.
bool AddLight(const Light &_light)
Add a light to the link.
const gz::math::Inertiald & Inertial() const
Get the inertial value for this link.
bool AddSensor(const Sensor &_sensor)
Add a sensor to the link.
Link()
Default constructor.
Projector * ProjectorByName(const std::string &_name)
Get a mutable projector based on a name.
const Sensor * SensorByIndex(const uint64_t _index) const
Get a sensor based on an index.
bool ParticleEmitterNameExists(const std::string &_name) const
Get whether a particle emitter name exists.
bool VisualNameExists(const std::string &_name) const
Get whether a visual name exists.
void ClearLights()
Remove all lights.
void SetName(const std::string &_name)
Set the name of the link.
bool CollisionNameExists(const std::string &_name) const
Get whether a collision name exists.
bool AutoInertiaSaved() const
Check if the inertial values for this link were saved.
const Projector * ProjectorByIndex(const uint64_t _index) const
Get a projector based on an index.
bool EnableWind() const
Check if this link should be subject to wind.
bool EnableGravity() const
Check if this link should be subject to gravity.
void SetDensity(double _density)
Set the density of the inertial.
void SetAutoInertia(bool _autoInertia)
Enable automatic inertial calculations by setting autoInertia to true.
const Projector * ProjectorByName(const std::string &_name) const
Get a projector based on a name.
const Sensor * SensorByName(const std::string &_name) const
Get a sensor based on a name.
Light * LightByIndex(uint64_t _index)
Get a mutable light based on an index.
Errors ResolveInertial(gz::math::Inertiald &_inertial, const std::string &_resolveTo="") const
Resolve the Inertial to a specified frame.
sdf::SemanticPose SemanticPose() const
Get SemanticPose object of this object to aid in resolving poses.
void SetAutoInertiaSaved(bool _autoInertiaSaved)
Set the autoInertiaSaved() values.
bool LightNameExists(const std::string &_name) const
Get whether a light name exists.
Sensor * SensorByName(const std::string &_name)
Get a mutable sensor based on a name.
const Collision * CollisionByName(const std::string &_name) const
Get a collision based on a name.
uint64_t SensorCount() const
Get the number of sensors.
bool SensorNameExists(const std::string &_name) const
Get whether a sensor name exists.
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
ParticleEmitter * ParticleEmitterByName(const std::string &_name)
Get a mutable particle emitter based on a name.
bool AddParticleEmitter(const ParticleEmitter &_emitter)
Add a particle emitter to the link.
void SetRawPose(const gz::math::Pose3d &_pose)
Set the pose of the link.
void ClearCollisions()
Remove all collisions.
bool AutoInertia() const
Check if the automatic calculation for the link inertial is enabled or not.
Visual * VisualByIndex(uint64_t _index)
Get a mutable visual based on an index.
Collision * CollisionByName(const std::string &_name)
Get a mutable collision based on a name.
Sensor * SensorByIndex(uint64_t _index)
Get a mutable sensor based on an index.
const Visual * VisualByIndex(const uint64_t _index) const
Get a visual based on an index.
sdf::ElementPtr AutoInertiaParams() const
Get the ElementPtr to the <auto_inertia_params> element This element can be used as a parent element ...
void ClearParticleEmitters()
Remove all particle emitters.
bool ProjectorNameExists(const std::string &_name) const
Get whether a projector name exists.
uint64_t ProjectorCount() const
Get the number of projectors.
bool AddProjector(const Projector &_projector)
Add a projector to the link.
void SetEnableGravity(bool _enableGravity)
Set whether this link should be subject to gravity.
bool AddVisual(const Visual &_visual)
Add a visual to the link.
This class contains configuration options for the libsdformat parser.
Definition: ParserConfig.hh:100
A description of a particle emitter, which can be attached to a link.
Definition: ParticleEmitter.hh:61
A description of a projector, which can be attached to a link.
Definition: Projector.hh:44
Definition: Collision.hh:44
SemanticPose is a data structure that can be used by different DOM objects to resolve poses on a Pose...
Definition: SemanticPose.hh:55
Information about an SDF sensor.
Definition: Sensor.hh:141
std::vector< Error > Errors
A vector of Error.
Definition: Types.hh:95
std::shared_ptr< Element > ElementPtr
Definition: Element.hh:55
namespace for Simulation Description Format parser
Definition: Actor.hh:35
#define SDFORMAT_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system_util.hh:25