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... | |
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 gz::math::Vector3d. More... | |
using | AngularVelocity = Component< math::Vector3d, class AngularVelocityTag > |
A component type that contains angular velocity of an entity represented by gz::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 gz::math::Vector3d. More... | |
using | Atmosphere = Component< sdf::Atmosphere, class AtmosphereTag, serializers::AtmosphereSerializer > |
This component holds atmosphere properties of the world. More... | |
using | AxisAlignedBox = Component< gz::math::AxisAlignedBox, class AxisAlignedBoxTag, serializers::AxisAlignedBoxSerializer > |
A component type that contains axis aligned box, gz::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, which is usually a link. More... | |
using | ChildLinkName = Component< std::string, class ChildLinkNameTag > |
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 gz::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 | 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 | JointEffortLimitsCmd = Component< std::vector< gz::math::Vector2d >, class JointEffortLimitsCmdTag, serializers::VectorSerializer< gz::math::Vector2d > > |
Command for setting effort limits of a joint. Data are a vector with a Vector2 for each DOF. The X() component of the Vector2 specifies the minimum effort limit, the Y() component stands for maximum limit. Set to +-infinity to disable the limits. 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 | JointPositionLimitsCmd = Component< std::vector< gz::math::Vector2d >, class JointPositionLimitsCmdTag, serializers::VectorSerializer< gz::math::Vector2d > > |
Command for setting position limits of a joint. Data are a vector with a Vector2 for each DOF. The X() component of the Vector2 specifies the minimum positional limit, the Y() component stands for maximum limit. Set to +-infinity to disable the limits. 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 | JointVelocityLimitsCmd = Component< std::vector< gz::math::Vector2d >, class JointVelocityLimitsCmdTag, serializers::VectorSerializer< gz::math::Vector2d > > |
Command for setting velocity limits of a joint. Data are a vector with a Vector2 for each DOF. The X() component of the Vector2 specifies the minimum velocity limit, the Y() component stands for maximum limit. Set to +-infinity to disable the limits. 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 | LinearAcceleration = Component< math::Vector3d, class LinearAccelerationTag > |
A component type that contains linear acceleration of an entity represented by gz::math::Vector3d. More... | |
using | LinearVelocity = Component< math::Vector3d, class LinearVelocityTag > |
A component type that contains linear velocity of an entity represented by gz::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 gz::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< gz::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 > |
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 > |
Holds the name of the entity's parent link. More... | |
using | Performer = Component< NoData, class PerformerTag > |
This component identifies an entity as being a performer. More... | |
using | PerformerAffinity = Component< std::string, class PerformerAffinityTag > |
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 > |
Holds the physics engine shared library. More... | |
using | Pose = Component< gz::math::Pose3d, class PoseTag > |
A component type that contains pose, gz::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 > |
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 | 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 | 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 gz::math::Pose3d. More... | |
Functions | |
IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.AngularAcceleration", AngularAcceleration) using WorldAngularAcceleration | |
A component type that contains angular acceleration of an entity in the world frame represented by gz::math::Vector3d. 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.CollisionElement", CollisionElement) using EnableContactSurfaceCustomization | |
A component used to enable customization of contact surface for a collision. The customization itself is done in callback of event CollectContactSurfaceProperties from PhysicsEvents. 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.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.World", World) using WorldSdf | |
A component that holds the world's SDF DOM. 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
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.
◆ 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 gz::math::Vector3d.
◆ AngularVelocity
using AngularVelocity = Component<math::Vector3d, class AngularVelocityTag> |
A component type that contains angular velocity of an entity represented by gz::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 gz::math::Vector3d.
◆ Atmosphere
using Atmosphere = Component<sdf::Atmosphere, class AtmosphereTag, serializers::AtmosphereSerializer> |
This component holds atmosphere properties of the world.
◆ AxisAlignedBox
using AxisAlignedBox = Component<gz::math::AxisAlignedBox, class AxisAlignedBoxTag, serializers::AxisAlignedBoxSerializer> |
A component type that contains axis aligned box, gz::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, which is usually a link.
◆ ChildLinkName
using ChildLinkName = Component<std::string, class ChildLinkNameTag> |
A component used to indicate that a model is childlinkname (i.e. not moveable).
◆ Collision
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
using ContactSensorData = Component<msgs::Contacts, class ContactSensorDataTag, serializers::MsgSerializer> |
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
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.
◆ 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 gz::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.
◆ Imu
using Imu = Component<sdf::Sensor, class ImuTag, serializers::SensorSerializer> |
A component type that contains an IMU sensor, sdf::IMU, information.
◆ Inertial
using Inertial = Component<math::Inertiald, class InertialTag, serializers::InertialSerializer> |
This component holds an entity's inertial.
◆ Joint
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.
◆ JointEffortLimitsCmd
using JointEffortLimitsCmd = Component< std::vector<gz::math::Vector2d>, class JointEffortLimitsCmdTag, serializers::VectorSerializer<gz::math::Vector2d> > |
Command for setting effort limits of a joint. Data are a vector with a Vector2 for each DOF. The X() component of the Vector2 specifies the minimum effort limit, the Y() component stands for maximum limit. Set to +-infinity to disable the limits.
- Note
- It is expected that the physics plugin reads this component and sets the limit to the dynamics engine. After setting it, the data of this component will be cleared (i.e. the vector will have length zero).
◆ 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.
◆ JointPositionLimitsCmd
using JointPositionLimitsCmd = Component< std::vector<gz::math::Vector2d>, class JointPositionLimitsCmdTag, serializers::VectorSerializer<gz::math::Vector2d> > |
Command for setting position limits of a joint. Data are a vector with a Vector2 for each DOF. The X() component of the Vector2 specifies the minimum positional limit, the Y() component stands for maximum limit. Set to +-infinity to disable the limits.
- Note
- It is expected that the physics plugin reads this component and sets the limit to the dynamics engine. After setting it, the data of this component will be cleared (i.e. the vector will have length zero).
◆ 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.
◆ JointVelocityLimitsCmd
using JointVelocityLimitsCmd = Component< std::vector<gz::math::Vector2d>, class JointVelocityLimitsCmdTag, serializers::VectorSerializer<gz::math::Vector2d> > |
Command for setting velocity limits of a joint. Data are a vector with a Vector2 for each DOF. The X() component of the Vector2 specifies the minimum velocity limit, the Y() component stands for maximum limit. Set to +-infinity to disable the limits.
- Note
- It is expected that the physics plugin reads this component and sets the limit to the dynamics engine. After setting it, the data of this component will be cleared (i.e. the vector will have length zero).
◆ 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
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
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.
◆ 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.
◆ LinearAcceleration
using LinearAcceleration = Component<math::Vector3d, class LinearAccelerationTag> |
A component type that contains linear acceleration of an entity represented by gz::math::Vector3d.
◆ LinearVelocity
using LinearVelocity = Component<math::Vector3d, class LinearVelocityTag> |
A component type that contains linear velocity of an entity represented by gz::math::Vector3d.
◆ LinearVelocityCmd
using LinearVelocityCmd = Component< math::Vector3d, class LinearVelocityCmdTag> |
entity represented by gz::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 gz::math::Vector3d. This seed can used to generate linear velocities by applying transformations and adding noise.
◆ Link
A component that identifies an entity as being a link.
◆ LogicalAudioSource
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.
◆ LogicalAudioSourcePlayInfo
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.
◆ 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
using LogicalMicrophone = Component<logical_audio::Microphone, class LogicalMicrophoneTag, serializers::LogicalMicrophoneSerializer> |
A component that contains a logical microphone, which is represented by logical_audio::Microphone.
◆ LogPlaybackStatistics
using LogPlaybackStatistics = Component<gz::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.
◆ 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
A component that identifies an entity as being a model.
◆ Name
using Name = Component<std::string, class NameTag> |
This component holds an entity's name. The component has no concept of scoped names nor does it care about uniqueness.
◆ NoData
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.
◆ 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 sim::SdfEntityCreator
class.
◆ ParentLinkName
using ParentLinkName = Component<std::string, class ParentLinkNameTag> |
Holds the name of the entity's parent link.
◆ Performer
This component identifies an entity as being a performer.
◆ PerformerAffinity
using PerformerAffinity = Component<std::string, class PerformerAffinityTag> |
This component holds the address of the distributed secondary that this performer is associated with.
◆ PerformerLevels
using PerformerLevels = Component<std::set<Entity>, class PerformerLevelsTag, serializers::PerformerLevelsSerializer> |
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
using PhysicsEnginePlugin = Component<std::string, class PhysicsEnginePluginTag> |
Holds the physics engine shared library.
◆ Pose
using Pose = Component<gz::math::Pose3d, class PoseTag> |
A component type that contains pose, gz::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
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
using SourceFilePath = Component<std::string, class SourceFilePathTag> |
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
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.
◆ 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).
◆ Visual
A component that identifies an entity as being a visual.
◆ Volume
A volume component where the units are m^3. Double value indicates volume of an entity.
◆ Wind
A component that identifies an entity as being a wind.
◆ WindMode
A component used to indicate whether an entity is affected by wind.
◆ World
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 gz::math::Pose3d.
Function Documentation
◆ IGN_GAZEBO_REGISTER_COMPONENT() [1/7]
IGN_GAZEBO_REGISTER_COMPONENT | ( | "ign_gazebo_components.AngularAcceleration" | , |
AngularAcceleration | |||
) |
A component type that contains angular acceleration of an entity in the world frame represented by gz::math::Vector3d.
A component type that contains pose, gz::math::Pose3d, information in world frame.
A component type that contains linear velocity seed of an entity in the world frame represented by gz::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 gz::math::Vector3d, expressed in the world frame.
A component type that contains linear velocity of an entity in the world frame represented by gz::math::Vector3d.
A component type that contains linear acceleration of an entity in the world frame represented by gz::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 gz::math::Vector3d.
A component type that contains angular velocity of an entity in the world frame represented by gz::math::Vector3d.
◆ IGN_GAZEBO_REGISTER_COMPONENT() [2/7]
ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT | ( | "ign_gazebo_components.Collision" | , |
Collision | |||
) |
A component that holds the sdf::Collision object.
◆ IGN_GAZEBO_REGISTER_COMPONENT() [3/7]
ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT | ( | "ign_gazebo_components.CollisionElement" | , |
CollisionElement | |||
) |
A component used to enable customization of contact surface for a collision. The customization itself is done in callback of event CollectContactSurfaceProperties from PhysicsEvents.
◆ IGN_GAZEBO_REGISTER_COMPONENT() [4/7]
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() [5/7]
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() [6/7]
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() [7/7]
ignition::gazebo::components::IGN_GAZEBO_REGISTER_COMPONENT | ( | "ign_gazebo_components.World" | , |
World | |||
) |
A component that holds the world's SDF DOM.