Ignition Gazebo

API Reference

5.1.0
ignition::gazebo::components Namespace Reference

Components represent data, such as position information. An Entity usually has one or more associated components. More...

Classes

class  BaseComponent
 Base class for all components. More...
 
class  Component
 A component type that wraps any data type. The intention is for this class to be used to create simple components while avoiding a lot of boilerplate code. The Identifier must be a unique type so that type aliases can be used to create new components. However the type does not need to be defined anywhere eg. More...
 
class  Component< NoData, Identifier, Serializer >
 Specialization for components that don't wrap any data. This class to be used to create simple components that represent just a "tag", while avoiding a lot of boilerplate code. The Identifier must be a unique type so that type aliases can be used to create new components. However the type does not need to be defined anywhere eg. More...
 
class  ComponentDescriptor
 A class for an object responsible for creating components. More...
 
class  ComponentDescriptorBase
 A base class for an object responsible for creating components. More...
 
struct  DetachableJointInfo
 Data structure to hold information about the parent and child links connected by a detachable joint. More...
 
class  Factory
 A factory that generates a component based on a string type. More...
 
class  StorageDescriptor
 A class for an object responsible for creating storages. More...
 
class  StorageDescriptorBase
 A base class for an object responsible for creating storages. More...
 
struct  TemperatureRangeInfo
 Data structure to hold a temperature range, in kelvin. More...
 

Typedefs

using Actor = Component< sdf::Actor, class ActorTag, serializers::ActorSerializer >
 This component contains actor source information. For more information on actors, see SDF's Actor element. More...
 
using Actuators = Component< msgs::Actuators, class ActuatorsTag, serializers::MsgSerializer >
 A component type that contains a msgs::Actuators message. This is used for example, to communicate between the MulticopterMotorModel and MulticopterVelocityControl systems. More...
 
using AirPressureSensor = Component< sdf::Sensor, class AirPressureSensorTag, serializers::SensorSerializer >
 A component type that contains an air pressure sensor, sdf::AirPressure, information. More...
 
using Altimeter = Component< sdf::Sensor, class AltimeterTag, serializers::SensorSerializer >
 A component type that contains an altimeter sensor, sdf::Altimeter, information. More...
 
using AngularAcceleration = Component< math::Vector3d, class AngularAccelerationTag >
 A component type that contains angular acceleration of an entity represented by ignition::math::Vector3d. More...
 
using AngularVelocity = Component< math::Vector3d, class AngularVelocityTag >
 A component type that contains angular velocity of an entity represented by ignition::math::Vector3d. More...
 
using AngularVelocityCmd = Component< math::Vector3d, class AngularVelocityCmdTag >
 A component type that contains the commanded angular velocity of an entity, in its own frame, represented by ignition::math::Vector3d. More...
 
using Atmosphere = Component< sdf::Atmosphere, class AtmosphereTag, serializers::AtmosphereSerializer >
 This component holds atmosphere properties of the world. More...
 
using AxisAlignedBox = Component< ignition::math::AxisAlignedBox, class AxisAlignedBoxTag, serializers::AxisAlignedBoxSerializer >
 A component type that contains axis aligned box, ignition::math::AxisAlignedBox, information. The axis aligned box is created from collisions in the entity. More...
 
using BatterySoC = Component< float, class BatterySoCTag >
 
using Camera = Component< sdf::Sensor, class CameraTag, serializers::SensorSerializer >
 A component type that contains a camera sensor, sdf::Camera, information. More...
 
using CanonicalLink = Component< NoData, class CanonicalLinkTag >
 A component that identifies an entity as being a canonical link. More...
 
using CastShadows = Component< bool, class CastShadowsTag >
 A component used to indicate that an entity casts shadows e.g. visual entities. More...
 
using CenterOfVolume = Component< math::Vector3d, class CenterOfVolumeTag >
 A component for an entity's center of volume. Units are in meters. The Vector3 value indicates center of volume of an entity. The position of the center of volume is relative to the pose of the parent entity. More...
 
using ChildLinkName = Component< std::string, class ChildLinkNameTag, serializers::StringSerializer >
 A component used to indicate that a model is childlinkname (i.e. not moveable). More...
 
using Collision = Component< NoData, class CollisionTag >
 A component that identifies an entity as being a collision. More...
 
using ContactSensor = Component< sdf::ElementPtr, class ContactSensorTag >
 TODO(anyone) Substitute with sdf::Contact once that exists? This is currently the whole <sensor> element. More...
 
using ContactSensorData = Component< msgs::Contacts, class ContactSensorDataTag, serializers::MsgSerializer >
 A component type that contains a list of contacts. More...
 
using DepthCamera = Component< sdf::Sensor, class DepthCameraTag, serializers::SensorSerializer >
 A component type that contains a depth camera sensor, sdf::Camera, information. More...
 
using DetachableJoint = Component< DetachableJointInfo, class DetachableJointTag, serializers::DetachableJointInfoSerializer >
 A component that identifies an entity as being a detachable joint. It also contains additional information about the joint. More...
 
using ExternalWorldWrenchCmd = Component< msgs::Wrench, class ExternalWorldWrenchCmdTag, serializers::MsgSerializer >
 A component type that contains the external wrench to be applied on an entity expressed in the world frame and represented by ignition::msgs::Wrench. Currently this is used for applying wrenches on links. Although the msg::Wrench type has a force_offset member, the value is currently ignored. Instead, the force is applied at the link origin. The wrench uses SI units (N for force and N⋅m for torque). More...
 
using Geometry = Component< sdf::Geometry, class GeometryTag, serializers::GeometrySerializer >
 This component holds an entity's geometry. More...
 
using GpuLidar = Component< sdf::Sensor, class GpuLidarTag, serializers::SensorSerializer >
 A component type that contains a GPU Lidar sensor, sdf::Lidar, information. More...
 
using Gravity = Component< math::Vector3d, class GravityTag >
 Store the gravity acceleration. More...
 
using HaltMotion = Component< bool, class HaltMotionTag >
 A component used to turn off a model's joint's movement. More...
 
using Imu = Component< sdf::Sensor, class ImuTag, serializers::SensorSerializer >
 A component type that contains an IMU sensor, sdf::IMU, information. More...
 
using Inertial = Component< math::Inertiald, class InertialTag, serializers::InertialSerializer >
 This component holds an entity's inertial. More...
 
using Joint = Component< NoData, class JointTag >
 A component that identifies an entity as being a joint. More...
 
using JointAxis = Component< sdf::JointAxis, class JointAxisTag, serializers::JointAxisSerializer >
 A component that contains the joint axis . This is a simple wrapper around sdf::JointAxis. More...
 
using JointForce = Component< std::vector< double >, class JointForceTag, serializers::VectorDoubleSerializer >
 Force applied to a joint in SI units (Nm for revolute, N for prismatic). More...
 
using JointForceCmd = Component< std::vector< double >, class JointForceCmdTag >
 Commanded joint forces (or torques) to be applied to a joint in SI units (Nm for revolute, N for prismatic). The component wraps a std::vector and systems that set this component need to ensure that the vector has the same size as the degrees of freedom of the joint. More...
 
using JointPosition = Component< std::vector< double >, class JointPositionTag, serializers::VectorDoubleSerializer >
 Joint positions in SI units (rad for revolute, m for prismatic). The component wraps a std::vector of size equal to the degrees of freedom of the joint. More...
 
using JointPositionReset = Component< std::vector< double >, class JointPositionResetTag, serializers::VectorDoubleSerializer >
 Joint positions in SI units (rad for revolute, m for prismatic). More...
 
using JointType = Component< sdf::JointType, class JointTypeTag, serializers::JointTypeSerializer >
 A component that contains the joint type. This is a simple wrapper around sdf::JointType. More...
 
using JointVelocity = Component< std::vector< double >, class JointVelocityTag, serializers::VectorDoubleSerializer >
 Base class which can be extended to add serialization. More...
 
using JointVelocityCmd = Component< std::vector< double >, class JointVelocityCmdTag, serializers::VectorDoubleSerializer >
 Base class which can be extended to add serialization. More...
 
using JointVelocityReset = Component< std::vector< double >, class JointVelocityResetTag, serializers::VectorDoubleSerializer >
 Joint velocities in SI units (rad/s for revolute, m/s for prismatic). More...
 
using LaserRetro = Component< double, class LaserRetroTag >
 A component used to indicate an lidar reflective value. More...
 
using Level = Component< NoData, class LevelTag >
 This component identifies an entity as being a level. More...
 
using LevelBuffer = Component< double, class LevelBufferTag >
 A component that holds the buffer setting of a level's geometry. More...
 
using LevelEntityNames = Component< std::set< std::string >, class LevelEntityNamesTag, serializers::LevelEntityNamesSerializer >
 A component that holds a list of names of entities to be loaded in a level. More...
 
using Lidar = Component< sdf::Sensor, class LidarTag, serializers::SensorSerializer >
 A component type that contains a Lidar sensor, sdf::Lidar, information. More...
 
using Light = Component< sdf::Light, class LightTag, serializers::LightSerializer >
 This component contains light source information. For more information on lights, see SDF's Light element. More...
 
using LightCmd = Component< ignition::msgs::Light, class LightCmdTag, serializers::MsgSerializer >
 A component type that contains commanded light of an entity in the world frame represented by msgs::Light. More...
 
using LightType = Component< std::string, class LightTypeTag, serializers::StringSerializer >
 A component that contains the light type. This is a simple wrapper around std::string. More...
 
using LinearAcceleration = Component< math::Vector3d, class LinearAccelerationTag >
 A component type that contains linear acceleration of an entity represented by ignition::math::Vector3d. More...
 
using LinearVelocity = Component< math::Vector3d, class LinearVelocityTag >
 A component type that contains linear velocity of an entity represented by ignition::math::Vector3d. More...
 
using LinearVelocityCmd = Component< math::Vector3d, class LinearVelocityCmdTag >
 
using LinearVelocitySeed = Component< math::Vector3d, class LinearVelocitySeedTag >
 A component type that contains linear velocity seed of an entity expressed in the local frame of the entity and represented by ignition::math::Vector3d. This seed can used to generate linear velocities by applying transformations and adding noise. More...
 
using Link = Component< NoData, class LinkTag >
 A component that identifies an entity as being a link. More...
 
using LogicalAudioSource = Component< logical_audio::Source, class LogicalAudioSourceTag, serializers::LogicalAudioSourceSerializer >
 A component that contains a logical audio source, which is represented by logical_audio::Source. More...
 
using LogicalAudioSourcePlayInfo = Component< logical_audio::SourcePlayInfo, class LogicalAudioSourcePlayInfoTag, serializers::LogicalAudioSourcePlayInfoSerializer >
 A component that contains a logical audio source's playing information, which is represented by logical_audio::SourcePlayInfo. More...
 
using LogicalCamera = Component< sdf::ElementPtr, class LogicalCameraTag >
 TODO(anyone) Substitute with sdf::LogicalCamera once that exists? This is currently the whole <sensor> element. More...
 
using LogicalMicrophone = Component< logical_audio::Microphone, class LogicalMicrophoneTag, serializers::LogicalMicrophoneSerializer >
 A component that contains a logical microphone, which is represented by logical_audio::Microphone. More...
 
using LogPlaybackStatistics = Component< ignition::msgs::LogPlaybackStatistics, class LogPlaybackStatisticsTag, serializers::MsgSerializer >
 A component type that contains log playback, systems::LogPlayback, information. The log playback is created from world entity upon the playback plugin being loaded. More...
 
using MagneticField = Component< math::Vector3d, class MagneticFieldTag >
 Stores the 3D magnetic field in teslas. More...
 
using Magnetometer = Component< sdf::Sensor, class MagnetometerTag, serializers::SensorSerializer >
 A component type that contains a magnetometer sensor, sdf::Magnetometer, information. More...
 
using Material = Component< sdf::Material, class MaterialTag, serializers::MaterialSerializer >
 This component holds an entity's material. More...
 
using Model = Component< NoData, class ModelTag >
 A component that identifies an entity as being a model. More...
 
using Name = Component< std::string, class NameTag, serializers::StringSerializer >
 This component holds an entity's name. The component has no concept of scoped names nor does it care about uniqueness. More...
 
using NoData = std::add_lvalue_reference< void >
 Convenient type to be used by components that don't wrap any data. I.e. they act as tags and their presence is enough to infer something about the entity. More...
 
using ParentEntity = Component< Entity, class ParentEntityTag >
 This component holds an entity's parent entity. More...
 
using ParentLinkName = Component< std::string, class ParentLinkNameTag, serializers::StringSerializer >
 Holds the name of the entity's parent link. More...
 
using ParticleEmitter = Component< msgs::ParticleEmitter, class ParticleEmitterTag, serializers::MsgSerializer >
 A component that contains a particle emitter. More...
 
using Performer = Component< NoData, class PerformerTag >
 This component identifies an entity as being a performer. More...
 
using PerformerAffinity = Component< std::string, class PerformerAffinityTag, serializers::StringSerializer >
 This component holds the address of the distributed secondary that this performer is associated with. More...
 
using PerformerLevels = Component< std::set< Entity >, class PerformerLevelsTag, serializers::PerformerLevelsSerializer >
 Holds all the levels which a performer is in. More...
 
using Physics = Component< sdf::Physics, class PhysicsTag, serializers::PhysicsSerializer >
 A component type that contains the physics properties of the World entity. More...
 
using PhysicsCmd = Component< msgs::Physics, class PhysicsCmdTag >
 A component type that contains the physics properties of the World entity. More...
 
using PhysicsEnginePlugin = Component< std::string, class PhysicsEnginePluginTag, serializers::StringSerializer >
 Holds the physics engine shared library. More...
 
using Pose = Component< ignition::math::Pose3d, class PoseTag >
 A component type that contains pose, ignition::math::Pose3d, information. More...
 
using RenderEngineGuiPlugin = Component< std::string, class RenderEngineGuiPluginTag, serializers::StringSerializer >
 Holds the render engine gui shared library. More...
 
using RenderEngineServerPlugin = Component< std::string, class RenderEngineServerPluginTag, serializers::StringSerializer >
 Holds the render engine server shared library. More...
 
using RgbdCamera = Component< sdf::Sensor, class RgbdCameraTag, serializers::SensorSerializer >
 A component type that contains a RGBD camera sensor, sdf::Camera, information. More...
 
using Scene = Component< sdf::Scene, class SceneTag, serializers::SceneSerializer >
 This component holds scene properties of the world. More...
 
using SelfCollide = Component< bool, class SelfCollideTag >
 A component used to hold a model's self collide property. More...
 
using Sensor = Component< NoData, class SensorTag >
 A component that identifies an entity as being a sensor. More...
 
using SlipComplianceCmd = Component< std::vector< double >, class SlipComplianceCmdTag >
 A component type that contains the slip compliance parameters to be set on a collision. The 0 and 1 index values correspond to the slip compliance parameters in friction direction 1 (fdir1) and friction direction 2 (fdir2) respectively. More...
 
using SourceFilePath = Component< std::string, class SourceFilePathTag, serializers::StringSerializer >
 This component holds the filepath to the source from which an entity is created. For example, it can be used to store the file path of a model's SDFormat file. More...
 
using Static = Component< bool, class StaticTag >
 A component used to indicate that a model is static (i.e. not moveable). More...
 
using Temperature = Component< math::Temperature, class TemperatureTag >
 A component that stores temperature data in Kelvin. More...
 
using TemperatureRange = Component< TemperatureRangeInfo, class TemperatureRangeTag, serializers::TemperatureRangeInfoSerializer >
 A component that stores a temperature range in kelvin. More...
 
using ThermalCamera = Component< sdf::Sensor, class ThermalCameraTag, serializers::SensorSerializer >
 A component type that contains a Thermal camera sensor, sdf::Sensor, information. More...
 
using ThreadPitch = Component< double, class ThreadPitchTag >
 A component used to store the thread pitch of a screw joint. More...
 
using Transparency = Component< float, class TransparencyTag >
 A component used to indicate an entity's transparency value e.g. visual entities. Value is in the range from 0 (opaque) to 1 (transparent). More...
 
using VisibilityFlags = Component< uint32_t, class VisibilityFlagsTag >
 This component holds an entity's visibility flags (visual entities) More...
 
using Visual = Component< NoData, class VisualTag >
 A component that identifies an entity as being a visual. More...
 
using Volume = Component< double, class VolumeTag >
 A volume component where the units are m^3. Double value indicates volume of an entity. More...
 
using Wind = Component< NoData, class WindTag >
 A component that identifies an entity as being a wind. More...
 
using WindMode = Component< bool, class WindModeTag >
 A component used to indicate whether an entity is affected by wind. More...
 
using World = Component< NoData, class WorldTag >
 A component that identifies an entity as being a world. More...
 
using WorldPoseCmd = Component< math::Pose3d, class WorldPoseCmdTag >
 A component type that contains commanded pose of an entity in the world frame represented by ignition::math::Pose3d. More...
 

Functions

 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.CanonicalLink", CanonicalLink) using ModelCanonicalLink
 A component that contains a reference to the canonical link entity of a model. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.VisibilityFlags", VisibilityFlags) using VisibilityMask
 This component holds an entity's visibility mask (camera sensor entities) More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.World", World) using WorldSdf
 A component that holds the world's SDF DOM. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.Sensor", Sensor) using SensorTopic
 Name of the transport topic where a sensor is publishing its data. For sensors that publish on more than one topic, this will usually be the prefix common to all topics of that sensor. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.Level", Level) using DefaultLevel
 This component identifies an entity as being a default level. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.Model", Model) using ModelSdf
 A component that holds the model's SDF DOM. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.WorldPose", WorldPose) using TrajectoryPose
 A component type that contains pose, ignition::math::Pose3d, information within a trajectory. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.Collision", Collision) using CollisionElement
 A component that holds the sdf::Collision object. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.PhysicsCollisionDetector", PhysicsCollisionDetector) using PhysicsSolver
 The name of the solver to be used. The supported options will depend on the physics engine being used. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.Actor", Actor) using AnimationTime
 Time in seconds within animation being currently played. More...
 
 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.AnimationTime", AnimationTime) using AnimationName
 Name of animation being currently played. More...
 

Detailed Description

Components represent data, such as position information. An Entity usually has one or more associated components.

The set of Components assigned to an Entity also act as a key. Systems process Entities based on their key. For example, a physics system may process only entities that have pose and inertia components.

Typedef Documentation

◆ Actor

using Actor = Component<sdf::Actor, class ActorTag, serializers::ActorSerializer>

This component contains actor source information. For more information on actors, see SDF's Actor element.

◆ Actuators

A component type that contains a msgs::Actuators message. This is used for example, to communicate between the MulticopterMotorModel and MulticopterVelocityControl systems.

◆ AirPressureSensor

using AirPressureSensor = Component<sdf::Sensor, class AirPressureSensorTag, serializers::SensorSerializer>

A component type that contains an air pressure sensor, sdf::AirPressure, information.

◆ Altimeter

using Altimeter = Component<sdf::Sensor, class AltimeterTag, serializers::SensorSerializer>

A component type that contains an altimeter sensor, sdf::Altimeter, information.

◆ AngularAcceleration

using AngularAcceleration = Component<math::Vector3d, class AngularAccelerationTag>

A component type that contains angular acceleration of an entity represented by ignition::math::Vector3d.

◆ AngularVelocity

using AngularVelocity = Component<math::Vector3d, class AngularVelocityTag>

A component type that contains angular velocity of an entity represented by ignition::math::Vector3d.

◆ AngularVelocityCmd

using AngularVelocityCmd = Component<math::Vector3d, class AngularVelocityCmdTag>

A component type that contains the commanded angular velocity of an entity, in its own frame, represented by ignition::math::Vector3d.

◆ Atmosphere

using Atmosphere = Component<sdf::Atmosphere, class AtmosphereTag, serializers::AtmosphereSerializer>

This component holds atmosphere properties of the world.

◆ AxisAlignedBox

A component type that contains axis aligned box, ignition::math::AxisAlignedBox, information. The axis aligned box is created from collisions in the entity.

◆ BatterySoC

using BatterySoC = Component<float, class BatterySoCTag>

A component that identifies an entity as being a battery. Float value indicates state of charge.

◆ Camera

using Camera = Component<sdf::Sensor, class CameraTag, serializers::SensorSerializer>

A component type that contains a camera sensor, sdf::Camera, information.

◆ CanonicalLink

using CanonicalLink = Component<NoData, class CanonicalLinkTag>

A component that identifies an entity as being a canonical link.

◆ CastShadows

using CastShadows = Component<bool, class CastShadowsTag>

A component used to indicate that an entity casts shadows e.g. visual entities.

◆ CenterOfVolume

using CenterOfVolume = Component<math::Vector3d, class CenterOfVolumeTag>

A component for an entity's center of volume. Units are in meters. The Vector3 value indicates center of volume of an entity. The position of the center of volume is relative to the pose of the parent entity.

◆ ChildLinkName

A component used to indicate that a model is childlinkname (i.e. not moveable).

◆ Collision

using Collision = Component<NoData, class CollisionTag>

A component that identifies an entity as being a collision.

◆ ContactSensor

using ContactSensor = Component<sdf::ElementPtr, class ContactSensorTag>

TODO(anyone) Substitute with sdf::Contact once that exists? This is currently the whole <sensor> element.

◆ ContactSensorData

A component type that contains a list of contacts.

◆ DepthCamera

using DepthCamera = Component<sdf::Sensor, class DepthCameraTag, serializers::SensorSerializer>

A component type that contains a depth camera sensor, sdf::Camera, information.

◆ DetachableJoint

A component that identifies an entity as being a detachable joint. It also contains additional information about the joint.

◆ ExternalWorldWrenchCmd

using ExternalWorldWrenchCmd = Component<msgs::Wrench, class ExternalWorldWrenchCmdTag, serializers::MsgSerializer>

A component type that contains the external wrench to be applied on an entity expressed in the world frame and represented by ignition::msgs::Wrench. Currently this is used for applying wrenches on links. Although the msg::Wrench type has a force_offset member, the value is currently ignored. Instead, the force is applied at the link origin. The wrench uses SI units (N for force and N⋅m for torque).

◆ Geometry

using Geometry = Component<sdf::Geometry, class GeometryTag, serializers::GeometrySerializer>

This component holds an entity's geometry.

◆ GpuLidar

using GpuLidar = Component<sdf::Sensor, class GpuLidarTag, serializers::SensorSerializer>

A component type that contains a GPU Lidar sensor, sdf::Lidar, information.

◆ Gravity

using Gravity = Component<math::Vector3d, class GravityTag>

Store the gravity acceleration.

◆ HaltMotion

using HaltMotion = Component<bool, class HaltMotionTag>

A component used to turn off a model's joint's movement.

◆ Imu

using Imu = Component<sdf::Sensor, class ImuTag, serializers::SensorSerializer>

A component type that contains an IMU sensor, sdf::IMU, information.

◆ Inertial

This component holds an entity's inertial.

◆ Joint

using Joint = Component<NoData, class JointTag>

A component that identifies an entity as being a joint.

◆ JointAxis

using JointAxis = Component<sdf::JointAxis, class JointAxisTag, serializers::JointAxisSerializer>

A component that contains the joint axis . This is a simple wrapper around sdf::JointAxis.

◆ JointForce

using JointForce = Component<std::vector<double>, class JointForceTag, serializers::VectorDoubleSerializer>

Force applied to a joint in SI units (Nm for revolute, N for prismatic).

◆ JointForceCmd

using JointForceCmd = Component<std::vector<double>, class JointForceCmdTag>

Commanded joint forces (or torques) to be applied to a joint in SI units (Nm for revolute, N for prismatic). The component wraps a std::vector and systems that set this component need to ensure that the vector has the same size as the degrees of freedom of the joint.

◆ JointPosition

using JointPosition = Component<std::vector<double>, class JointPositionTag, serializers::VectorDoubleSerializer>

Joint positions in SI units (rad for revolute, m for prismatic). The component wraps a std::vector of size equal to the degrees of freedom of the joint.

◆ JointPositionReset

using JointPositionReset = Component<std::vector<double>, class JointPositionResetTag, serializers::VectorDoubleSerializer>

Joint positions in SI units (rad for revolute, m for prismatic).

The component wraps a std::vector of size equal to the degrees of freedom of the joint.

◆ JointType

using JointType = Component<sdf::JointType, class JointTypeTag, serializers::JointTypeSerializer>

A component that contains the joint type. This is a simple wrapper around sdf::JointType.

◆ JointVelocity

using JointVelocity = Component<std::vector<double>, class JointVelocityTag, serializers::VectorDoubleSerializer>

Base class which can be extended to add serialization.

◆ JointVelocityCmd

using JointVelocityCmd = Component<std::vector<double>, class JointVelocityCmdTag, serializers::VectorDoubleSerializer>

Base class which can be extended to add serialization.

◆ JointVelocityReset

using JointVelocityReset = Component<std::vector<double>, class JointVelocityResetTag, serializers::VectorDoubleSerializer>

Joint velocities in SI units (rad/s for revolute, m/s for prismatic).

The component wraps a std::vector of size equal to the degrees of freedom of the joint.

◆ LaserRetro

using LaserRetro = Component<double, class LaserRetroTag>

A component used to indicate an lidar reflective value.

◆ Level

using Level = Component<NoData, class LevelTag>

This component identifies an entity as being a level.

◆ LevelBuffer

using LevelBuffer = Component<double, class LevelBufferTag>

A component that holds the buffer setting of a level's geometry.

◆ LevelEntityNames

A component that holds a list of names of entities to be loaded in a level.

◆ Lidar

using Lidar = Component<sdf::Sensor, class LidarTag, serializers::SensorSerializer>

A component type that contains a Lidar sensor, sdf::Lidar, information.

◆ Light

using Light = Component<sdf::Light, class LightTag, serializers::LightSerializer>

This component contains light source information. For more information on lights, see SDF's Light element.

◆ LightCmd

A component type that contains commanded light of an entity in the world frame represented by msgs::Light.

◆ LightType

A component that contains the light type. This is a simple wrapper around std::string.

◆ LinearAcceleration

using LinearAcceleration = Component<math::Vector3d, class LinearAccelerationTag>

A component type that contains linear acceleration of an entity represented by ignition::math::Vector3d.

◆ LinearVelocity

using LinearVelocity = Component<math::Vector3d, class LinearVelocityTag>

A component type that contains linear velocity of an entity represented by ignition::math::Vector3d.

◆ LinearVelocityCmd

using LinearVelocityCmd = Component< math::Vector3d, class LinearVelocityCmdTag>

entity represented by ignition::math::Vector3d, expressed in the entity's frame.

◆ LinearVelocitySeed

using LinearVelocitySeed = Component<math::Vector3d, class LinearVelocitySeedTag>

A component type that contains linear velocity seed of an entity expressed in the local frame of the entity and represented by ignition::math::Vector3d. This seed can used to generate linear velocities by applying transformations and adding noise.

◆ Link

using Link = Component<NoData, class LinkTag>

A component that identifies an entity as being a link.

◆ LogicalAudioSource

A component that contains a logical audio source, which is represented by logical_audio::Source.

◆ LogicalAudioSourcePlayInfo

A component that contains a logical audio source's playing information, which is represented by logical_audio::SourcePlayInfo.

◆ LogicalCamera

using LogicalCamera = Component<sdf::ElementPtr, class LogicalCameraTag>

TODO(anyone) Substitute with sdf::LogicalCamera once that exists? This is currently the whole <sensor> element.

◆ LogicalMicrophone

A component that contains a logical microphone, which is represented by logical_audio::Microphone.

◆ LogPlaybackStatistics

A component type that contains log playback, systems::LogPlayback, information. The log playback is created from world entity upon the playback plugin being loaded.

◆ MagneticField

using MagneticField = Component<math::Vector3d, class MagneticFieldTag>

Stores the 3D magnetic field in teslas.

◆ Magnetometer

using Magnetometer = Component<sdf::Sensor, class MagnetometerTag, serializers::SensorSerializer>

A component type that contains a magnetometer sensor, sdf::Magnetometer, information.

◆ Material

using Material = Component<sdf::Material, class MaterialTag, serializers::MaterialSerializer>

This component holds an entity's material.

◆ Model

using Model = Component<NoData, class ModelTag>

A component that identifies an entity as being a model.

◆ Name

This component holds an entity's name. The component has no concept of scoped names nor does it care about uniqueness.

◆ NoData

Convenient type to be used by components that don't wrap any data. I.e. they act as tags and their presence is enough to infer something about the entity.

◆ ParentEntity

using ParentEntity = Component<Entity, class ParentEntityTag>

This component holds an entity's parent entity.

Note that the EntityComponentManager also keeps the parent-child relationship stored in a graph, and that information should be kept in sync with the parent entity components. Therefore, it is recommended that the ParentEntity component is never edited by hand, and instead, entities should be created using the gazebo::SdfEntityCreator class.

◆ ParentLinkName

Holds the name of the entity's parent link.

◆ ParticleEmitter

A component that contains a particle emitter.

◆ Performer

using Performer = Component<NoData, class PerformerTag>

This component identifies an entity as being a performer.

◆ PerformerAffinity

This component holds the address of the distributed secondary that this performer is associated with.

◆ PerformerLevels

Holds all the levels which a performer is in.

◆ Physics

using Physics = Component<sdf::Physics, class PhysicsTag, serializers::PhysicsSerializer>

A component type that contains the physics properties of the World entity.

◆ PhysicsCmd

using PhysicsCmd = Component<msgs::Physics, class PhysicsCmdTag>

A component type that contains the physics properties of the World entity.

◆ PhysicsEnginePlugin

Holds the physics engine shared library.

◆ Pose

using Pose = Component<ignition::math::Pose3d, class PoseTag>

A component type that contains pose, ignition::math::Pose3d, information.

◆ RenderEngineGuiPlugin

using RenderEngineGuiPlugin = Component<std::string, class RenderEngineGuiPluginTag, serializers::StringSerializer>

Holds the render engine gui shared library.

◆ RenderEngineServerPlugin

using RenderEngineServerPlugin = Component<std::string, class RenderEngineServerPluginTag, serializers::StringSerializer>

Holds the render engine server shared library.

◆ RgbdCamera

using RgbdCamera = Component<sdf::Sensor, class RgbdCameraTag, serializers::SensorSerializer>

A component type that contains a RGBD camera sensor, sdf::Camera, information.

◆ Scene

using Scene = Component<sdf::Scene, class SceneTag, serializers::SceneSerializer>

This component holds scene properties of the world.

◆ SelfCollide

using SelfCollide = Component<bool, class SelfCollideTag>

A component used to hold a model's self collide property.

◆ Sensor

using Sensor = Component<NoData, class SensorTag>

A component that identifies an entity as being a sensor.

◆ SlipComplianceCmd

using SlipComplianceCmd = Component<std::vector<double>, class SlipComplianceCmdTag>

A component type that contains the slip compliance parameters to be set on a collision. The 0 and 1 index values correspond to the slip compliance parameters in friction direction 1 (fdir1) and friction direction 2 (fdir2) respectively.

◆ SourceFilePath

This component holds the filepath to the source from which an entity is created. For example, it can be used to store the file path of a model's SDFormat file.

◆ Static

using Static = Component<bool, class StaticTag>

A component used to indicate that a model is static (i.e. not moveable).

◆ Temperature

using Temperature = Component<math::Temperature, class TemperatureTag>

A component that stores temperature data in Kelvin.

◆ TemperatureRange

A component that stores a temperature range in kelvin.

◆ ThermalCamera

using ThermalCamera = Component<sdf::Sensor, class ThermalCameraTag, serializers::SensorSerializer>

A component type that contains a Thermal camera sensor, sdf::Sensor, information.

◆ ThreadPitch

using ThreadPitch = Component<double, class ThreadPitchTag>

A component used to store the thread pitch of a screw joint.

◆ Transparency

using Transparency = Component<float, class TransparencyTag>

A component used to indicate an entity's transparency value e.g. visual entities. Value is in the range from 0 (opaque) to 1 (transparent).

◆ VisibilityFlags

using VisibilityFlags = Component<uint32_t, class VisibilityFlagsTag>

This component holds an entity's visibility flags (visual entities)

◆ Visual

using Visual = Component<NoData, class VisualTag>

A component that identifies an entity as being a visual.

◆ Volume

using Volume = Component<double, class VolumeTag>

A volume component where the units are m^3. Double value indicates volume of an entity.

◆ Wind

using Wind = Component<NoData, class WindTag>

A component that identifies an entity as being a wind.

◆ WindMode

using WindMode = Component<bool, class WindModeTag>

A component used to indicate whether an entity is affected by wind.

◆ World

using World = Component<NoData, class WorldTag>

A component that identifies an entity as being a world.

◆ WorldPoseCmd

using WorldPoseCmd = Component<math::Pose3d, class WorldPoseCmdTag>

A component type that contains commanded pose of an entity in the world frame represented by ignition::math::Pose3d.

Function Documentation

◆ IGN_GAZEBO_REGISTER_COMPONENT() [1/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.CanonicalLink"  ,
CanonicalLink   
)

A component that contains a reference to the canonical link entity of a model.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [2/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.VisibilityFlags"  ,
VisibilityFlags   
)

This component holds an entity's visibility mask (camera sensor entities)

◆ IGN_GAZEBO_REGISTER_COMPONENT() [3/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.World"  ,
World   
)

A component that holds the world's SDF DOM.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [4/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.Sensor"  ,
Sensor   
)

Name of the transport topic where a sensor is publishing its data. For sensors that publish on more than one topic, this will usually be the prefix common to all topics of that sensor.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [5/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.Level"  ,
Level   
)

This component identifies an entity as being a default level.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [6/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.Model"  ,
Model   
)

A component that holds the model's SDF DOM.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [7/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.WorldPose"  ,
WorldPose   
)

A component type that contains pose, ignition::math::Pose3d, information within a trajectory.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [8/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.Collision"  ,
Collision   
)

A component that holds the sdf::Collision object.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [9/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.PhysicsCollisionDetector"  ,
PhysicsCollisionDetector   
)

The name of the solver to be used. The supported options will depend on the physics engine being used.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [10/11]

IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.Actor"  ,
Actor   
)
Initial value:
=
Component<math::Vector3d, class WorldAngularAccelerationTag>

Time in seconds within animation being currently played.

A component that stores temperature linear resolution in Kelvin.

A component type that contains pose, ignition::math::Pose3d, information in world frame.

The name of the collision detector to be used. The supported options will depend on the physics engine being used.

A component that contains a particle emitter command.

A component type that contains linear velocity seed of an entity in the world frame represented by ignition::math::Vector3d. This seed can used to generate linear velocities by applying transformations and adding noise.

A component type that contains the commanded linear velocity of an entity represented by ignition::math::Vector3d, expressed in the world frame.

A component type that contains linear velocity of an entity in the world frame represented by ignition::math::Vector3d.

A component type that contains linear acceleration of an entity in the world frame represented by ignition::math::Vector3d.

A component that contains the second joint axis for joints with two axes. This is a simple wrapper around sdf::JointAxis.

A component type that contains the commanded angular velocity of an entity in the world frame represented by ignition::math::Vector3d.

A component type that contains angular velocity of an entity in the world frame represented by ignition::math::Vector3d.

A component type that contains angular acceleration of an entity in the world frame represented by ignition::math::Vector3d.

◆ IGN_GAZEBO_REGISTER_COMPONENT() [11/11]

ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.AnimationTime"  ,
AnimationTime   
)

Name of animation being currently played.