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... | |
struct | BatteryPowerLoadInfo |
Data structure to hold the consumer power load and the name of the battery it uses. 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... | |
class | ComponentDescriptorQueue |
A class to hold the queue of component descriptors registered by translation units. This queue is necessary to ensure that component creation continues to work after plugins are unloaded. The typical scenario this aims to solve is: More... | |
struct | DetachableJointInfo |
Data structure to hold information about the parent and child links connected by a detachable joint. More... | |
struct | EnvironmentalData |
Environment data across time and space. This is useful to introduce physical quantities that may be of interest even if not modelled in simulation. More... | |
class | Factory |
A factory that generates a component based on a string type. More... | |
struct | RaycastDataInfo |
A struct that holds the raycasting data, including ray and results. More... | |
struct | RaycastResultInfo |
A struct that holds the result of a raycasting operation. More... | |
struct | RayInfo |
A struct that holds the information of a ray. More... | |
struct | RegistrationObjectId |
A wrapper around uintptr_t to prevent implicit conversions. 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 | AirSpeedSensor = Component< sdf::Sensor, class AirSpeedSensorTag, serializers::SensorSerializer > |
A component type that contains an air speed sensor, sdf::AirSpeed, 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 | BatteryPowerLoad = Component< BatteryPowerLoadInfo, class BatteryPowerLoadTag > |
A component that indicates the total consumption of a battery. More... | |
using | BatterySoC = Component< float, class BatterySoCTag > |
using | BoundingBoxCamera = Component< sdf::Sensor, class BoundingBoxCameraTag, serializers::SensorSerializer > |
A component type that contains a BoundingBox camera sensor, sdf::Camera, information. More... | |
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, 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 | CustomSensor = Component< sdf::Sensor, class CustomSensorTag, serializers::SensorSerializer > |
A component type that contains a custom sensor's information. A custom sensor is any sensor that's not officially supported through the SDF spec. 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 | Environment = Component< std::shared_ptr< EnvironmentalData >, class EnvironmentalDataTag > |
A component type that contains a environment data. Ownership is shared to avoid data copies unless necessary. 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 | ForceTorque = Component< sdf::Sensor, class ForceTorqueTag, serializers::SensorSerializer > |
A component type that contains an FT sensor, sdf::ForceTorque, information. 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 | 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 | JointTransmittedWrench = Component< msgs::Wrench, class JointTransmittedWrenchTag, serializers::MsgSerializer > |
Joint Transmitted wrench in SI units (Nm for torque, N for force). The wrench is expressed in the Joint frame and the force component is applied at the joint origin. 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 | LightCmd = Component< gz::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 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, 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 | NavSat = Component< sdf::Sensor, class NavSatTag, serializers::SensorSerializer > |
A component type that contains an NavSat sensor, sdf::NavSat, information. 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< gz::math::Pose3d, class PoseTag > |
A component type that contains pose, gz::math::Pose3d, information. More... | |
using | Projector = Component< sdf::Projector, class ProjectorTag, serializers::ProjectorSerializer > |
A component type that contains a projector, sdf::Projector, information. More... | |
using | RaycastData = Component< RaycastDataInfo, class RaycastDataTag, serializers::DefaultSerializer< RaycastDataInfo > > |
A component type that contains the rays traced from an entity into a physics world, along with the results of the raycasting operation. More... | |
using | Recreate = Component< NoData, class RecreateTag > |
A component that identifies an entity needs to be recreated. Currently, only Models will be processed for recreation by the SimulationRunner in the ProcessRecreateEntitiesRemove and ProcessRecreateEntitiesCreate functions. More... | |
using | RenderEngineGuiPlugin = Component< std::string, class RenderEngineGuiPluginTag, serializers::StringSerializer > |
Holds the render engine gui shared library. More... | |
using | RenderEngineServerApiBackend = Component< std::string, class RenderEngineServerApiBackendTag, serializers::StringSerializer > |
Holds the render engine server API backend name. More... | |
using | RenderEngineServerHeadless = Component< bool, class RenderEngineServerHeadlessTag > |
Holds the headless mode. 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 | SegmentationCamera = Component< sdf::Sensor, class SegmentationCameraTag, serializers::SensorSerializer > |
A component type that contains a Segmentation camera sensor, sdf::Camera, information. More... | |
using | SelfCollide = Component< bool, class SelfCollideTag > |
A component used to hold a model's self collide property. More... | |
using | SemanticLabel = Component< uint32_t, class SemanticLabelTag > |
A component that holds the label of an entity. One example use case of the Label component is with Segmentation & Bounding box sensors to generate dataset annotations. 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 | SphericalCoordinates = Component< math::SphericalCoordinates, class SphericalCoordinatesTag, serializers::SphericalCoordinatesSerializer > |
This component holds the spherical coordinates of the world origin. More... | |
using | Static = Component< bool, class StaticTag > |
A component used to indicate that a model is static (i.e. not moveable). More... | |
using | SystemPluginInfo = Component< msgs::Plugin_V, class SystemPluginInfoTag, serializers::MsgSerializer > |
This component holds information about all the system plugins that are attached to an entity. The content of each system is populated the moment the plugin is instantiated and isn't modified throughout simulation. 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 | VisualCmd = Component< gz::msgs::Visual, class VisualCmdTag, serializers::MsgSerializer > |
A component type that contains commanded visual of an entity in the world frame represented by msgs::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 | WheelSlipCmd = Component< gz::msgs::WheelSlipParametersCmd, class WheelSlipCmdTag, serializers::MsgSerializer > |
A component type that contains commanded wheel slip parameters of an entity in the world frame represented by msgs::WheelSlipParameters. More... | |
using | WideAngleCamera = Component< sdf::Sensor, class WideAngleCameraTag, serializers::SensorSerializer > |
A component type that contains a wide angle camera sensor, sdf::Camera, information. 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... | |
using | WrenchMeasured = Component< msgs::Wrench, class WrenchMeasuredTag, serializers::MsgSerializer > |
Wrench measured by a ForceTorqueSensor in SI units (Nm for torque, N for force). The wrench is expressed in the Sensor frame and the force component is applied at the sensor origin. More... | |
Functions | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.Actor", Actor) using AnimationTime | |
Time in seconds within animation being currently played. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.AnimationTime", AnimationTime) using AnimationName | |
Name of animation being currently played. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.CanonicalLink", CanonicalLink) using ModelCanonicalLink | |
A component that contains a reference to the canonical link entity of a model. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.Collision", Collision) using CollisionElement | |
A component that holds the sdf::Collision object. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_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... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.Level", Level) using DefaultLevel | |
This component identifies an entity as being a default level. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.Model", Model) using ModelSdf | |
A component that holds the model's SDF DOM. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.Performer", Performer) using PerformerRef | |
This component contains the performer reference name. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_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... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_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... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.VisibilityFlags", VisibilityFlags) using VisibilityMask | |
This component holds an entity's visibility mask (camera sensor entities) More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.Visual", Visual) using VisualPlugin | |
A component that contains a visual plugin's SDF element. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.World", World) using WorldSdf | |
A component that holds the world's SDF DOM. More... | |
GZ_SIM_REGISTER_COMPONENT ("gz_sim_components.WorldPose", WorldPose) using TrajectoryPose | |
A component type that contains pose, gz::math::Pose3d, information within a trajectory. 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.
šAirSpeedSensor
using AirSpeedSensor = Component<sdf::Sensor, class AirSpeedSensorTag, serializers::SensorSerializer> |
A component type that contains an air speed sensor, sdf::AirSpeed, 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.
šBatteryPowerLoad
using BatteryPowerLoad = Component<BatteryPowerLoadInfo, class BatteryPowerLoadTag> |
A component that indicates the total consumption of a battery.
šBatterySoC
using BatterySoC = Component<float, class BatterySoCTag> |
A component that identifies an entity as being a battery. Float value indicates state of charge.
šBoundingBoxCamera
using BoundingBoxCamera = Component<sdf::Sensor, class BoundingBoxCameraTag, serializers::SensorSerializer> |
A component type that contains a BoundingBox camera sensor, sdf::Camera, information.
š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, serializers::StringSerializer> |
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.
šCustomSensor
using CustomSensor = Component<sdf::Sensor, class CustomSensorTag, serializers::SensorSerializer> |
A component type that contains a custom sensor's information. A custom sensor is any sensor that's not officially supported through the SDF spec.
š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.
šEnvironment
using Environment = Component<std::shared_ptr<EnvironmentalData>, class EnvironmentalDataTag> |
A component type that contains a environment data. Ownership is shared to avoid data copies unless necessary.
š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).
šForceTorque
using ForceTorque = Component<sdf::Sensor, class ForceTorqueTag, serializers::SensorSerializer> |
A component type that contains an FT sensor, sdf::ForceTorque, information.
š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
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.
šJointTransmittedWrench
using JointTransmittedWrench = Component<msgs::Wrench, class JointTransmittedWrenchTag, serializers::MsgSerializer> |
Joint Transmitted wrench in SI units (Nm for torque, N for force). The wrench is expressed in the Joint frame and the force component is applied at the joint origin.
- Note
- The term Wrench is used here to mean a pair of 3D vectors representing torque and force quantities expressed in a given frame and where the force is applied at the origin of the frame. This is different from the Wrench used in screw theory.
- The value of force_offset in msgs::Wrench is ignored for this component. The force is assumed to be applied at the origin of the joint frame.
š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.
šLightCmd
using LightCmd = Component<gz::msgs::Light, class LightCmdTag, serializers::MsgSerializer> |
A component type that contains commanded light of an entity in the world frame represented by msgs::Light.
šLightType
using LightType = Component<std::string, class LightTypeTag, serializers::StringSerializer> |
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 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, serializers::StringSerializer> |
This component holds an entity's name. The component has no concept of scoped names nor does it care about uniqueness.
šNavSat
using NavSat = Component<sdf::Sensor, class NavSatTag, serializers::SensorSerializer> |
A component type that contains an NavSat sensor, sdf::NavSat, information.
š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, serializers::StringSerializer> |
Holds the name of the entity's parent link.
šParticleEmitter
using ParticleEmitter = Component<msgs::ParticleEmitter, class ParticleEmitterTag, serializers::MsgSerializer> |
A component that contains a particle emitter.
šPerformer
This component identifies an entity as being a performer.
šPerformerAffinity
using PerformerAffinity = Component<std::string, class PerformerAffinityTag, serializers::StringSerializer> |
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, serializers::StringSerializer> |
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.
šProjector
using Projector = Component<sdf::Projector, class ProjectorTag, serializers::ProjectorSerializer> |
A component type that contains a projector, sdf::Projector, information.
šRaycastData
using RaycastData = Component<RaycastDataInfo, class RaycastDataTag, serializers::DefaultSerializer<RaycastDataInfo> > |
A component type that contains the rays traced from an entity into a physics world, along with the results of the raycasting operation.
This component is primarily used for applications that require raycasting. The target application defines the rays, and the physics system plugin updates the raycasting results during each update loop.
šRecreate
A component that identifies an entity needs to be recreated. Currently, only Models will be processed for recreation by the SimulationRunner in the ProcessRecreateEntitiesRemove and ProcessRecreateEntitiesCreate functions.
The GUI ModelEditor contains example code on how to use this component. For example, the ModelEditor allows a user to add a link to an existing model. The existing model is tagged with this component so that it can be recreated by the server.
šRenderEngineGuiPlugin
using RenderEngineGuiPlugin = Component<std::string, class RenderEngineGuiPluginTag, serializers::StringSerializer> |
Holds the render engine gui shared library.
šRenderEngineServerApiBackend
using RenderEngineServerApiBackend = Component<std::string, class RenderEngineServerApiBackendTag, serializers::StringSerializer> |
Holds the render engine server API backend name.
šRenderEngineServerHeadless
using RenderEngineServerHeadless = Component<bool, class RenderEngineServerHeadlessTag> |
Holds the headless mode.
š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.
šSegmentationCamera
using SegmentationCamera = Component<sdf::Sensor, class SegmentationCameraTag, serializers::SensorSerializer> |
A component type that contains a Segmentation camera sensor, sdf::Camera, information.
šSelfCollide
using SelfCollide = Component<bool, class SelfCollideTag> |
A component used to hold a model's self collide property.
šSemanticLabel
using SemanticLabel = Component<uint32_t, class SemanticLabelTag> |
A component that holds the label of an entity. One example use case of the Label component is with Segmentation & Bounding box sensors to generate dataset annotations.
š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, 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.
šSphericalCoordinates
using SphericalCoordinates = Component<math::SphericalCoordinates, class SphericalCoordinatesTag, serializers::SphericalCoordinatesSerializer> |
This component holds the spherical coordinates of the world origin.
šStatic
A component used to indicate that a model is static (i.e. not moveable).
šSystemPluginInfo
using SystemPluginInfo = Component<msgs::Plugin_V, class SystemPluginInfoTag, serializers::MsgSerializer> |
This component holds information about all the system plugins that are attached to an entity. The content of each system is populated the moment the plugin is instantiated and isn't modified throughout simulation.
šTemperature
using Temperature = Component<math::Temperature, class TemperatureTag> |
A component that stores temperature data in Kelvin.
šTemperatureRange
using TemperatureRange = Component<TemperatureRangeInfo, class TemperatureRangeTag, serializers::TemperatureRangeInfoSerializer> |
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
A component that identifies an entity as being a visual.
šVisualCmd
using VisualCmd = Component<gz::msgs::Visual, class VisualCmdTag, serializers::MsgSerializer> |
A component type that contains commanded visual of an entity in the world frame represented by msgs::Visual.
šVolume
A volume component where the units are m^3. Double value indicates volume of an entity.
šWheelSlipCmd
using WheelSlipCmd = Component<gz::msgs::WheelSlipParametersCmd, class WheelSlipCmdTag, serializers::MsgSerializer> |
A component type that contains commanded wheel slip parameters of an entity in the world frame represented by msgs::WheelSlipParameters.
šWideAngleCamera
using WideAngleCamera = Component<sdf::Sensor, class WideAngleCameraTag, serializers::SensorSerializer> |
A component type that contains a wide angle camera sensor, sdf::Camera, information.
š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.
šWrenchMeasured
using WrenchMeasured = Component<msgs::Wrench, class WrenchMeasuredTag, serializers::MsgSerializer> |
Wrench measured by a ForceTorqueSensor in SI units (Nm for torque, N for force). The wrench is expressed in the Sensor frame and the force component is applied at the sensor origin.
- Note
- The term Wrench is used here to mean a pair of 3D vectors representing torque and force quantities expressed in a given frame and where the force is applied at the origin of the frame. This is different from the Wrench used in screw theory.
- The value of force_offset in msgs::Wrench is ignored for this component. The force is assumed to be applied at the origin of the sensor frame.
Function Documentation
šGZ_SIM_REGISTER_COMPONENT() [1/14]
GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.Actor" | , |
Actor | |||
) |
Time in seconds within animation being currently played.
A component that stores temperature linear resolution in Kelvin.
A component type that contains pose, gz::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 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.
Store the gravity acceleration.
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.
A component type that contains angular acceleration of an entity in the world frame represented by gz::math::Vector3d.
šGZ_SIM_REGISTER_COMPONENT() [2/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.AnimationTime" | , |
AnimationTime | |||
) |
Name of animation being currently played.
šGZ_SIM_REGISTER_COMPONENT() [3/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.CanonicalLink" | , |
CanonicalLink | |||
) |
A component that contains a reference to the canonical link entity of a model.
šGZ_SIM_REGISTER_COMPONENT() [4/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.Collision" | , |
Collision | |||
) |
A component that holds the sdf::Collision object.
šGZ_SIM_REGISTER_COMPONENT() [5/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_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.
šGZ_SIM_REGISTER_COMPONENT() [6/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.Level" | , |
Level | |||
) |
This component identifies an entity as being a default level.
šGZ_SIM_REGISTER_COMPONENT() [7/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.Model" | , |
Model | |||
) |
A component that holds the model's SDF DOM.
šGZ_SIM_REGISTER_COMPONENT() [8/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.Performer" | , |
Performer | |||
) |
This component contains the performer reference name.
šGZ_SIM_REGISTER_COMPONENT() [9/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.PhysicsCollisionDetector" | , |
PhysicsCollisionDetector | |||
) |
The name of the solver to be used. The supported options will depend on the physics engine being used.
šGZ_SIM_REGISTER_COMPONENT() [10/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_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.
šGZ_SIM_REGISTER_COMPONENT() [11/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.VisibilityFlags" | , |
VisibilityFlags | |||
) |
This component holds an entity's visibility mask (camera sensor entities)
šGZ_SIM_REGISTER_COMPONENT() [12/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.Visual" | , |
Visual | |||
) |
A component that contains a visual plugin's SDF element.
šGZ_SIM_REGISTER_COMPONENT() [13/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.World" | , |
World | |||
) |
A component that holds the world's SDF DOM.
šGZ_SIM_REGISTER_COMPONENT() [14/14]
gz::sim::components::GZ_SIM_REGISTER_COMPONENT | ( | "gz_sim_components.WorldPose" | , |
WorldPose | |||
) |
A component type that contains pose, gz::math::Pose3d, information within a trajectory.