Ignition Gazebo

API Reference

1.0.2
ignition::gazebo::components Namespace Reference

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

Classes

class  BaseComponent
 Base class for all components. More...
 
class  Component
 A component type that wraps any data type. The intention is for this class to be used to create simple components while avoiding a lot of boilerplate code. The Identifier must be a unique type so that type aliases can be used to create new components. However the type does not need to be defined anywhere eg. using Static = Component<bool, class StaticTag>;. More...
 
class  Component< NoData, Identifier >
 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  ComponentPrivate
 
class  Factory
 A factory that generates a component based on a string type. More...
 
class  LevelEntityNames
 A component that holds a list of names of entities to be loaded in a level. 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 Altimeter = Component< sdf::ElementPtr, class AltimeterTag >
 TODO(anyone) Substitute with sdf::Altimeter once that exists? This is currently the whole <sensor> element. More...
 
using AngularVelocity = Component< math::Vector3d, class AngularVelocityTag >
 A component type that contains angular velocity of an entity represented by ignition::math::Vector3d. More...
 
using Camera = Component< sdf::ElementPtr, class CameraTag >
 TODO(louise) Substitute with sdf::Camera once that exists? This is currently the whole <sensor> element. More...
 
using CanonicalLink = Component< NoData, class CanonicalLinkTag >
 A component that identifies an entity as being a canonical 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 >
 A component type that contains a list of contacts. More...
 
using DepthCamera = Component< sdf::ElementPtr, class DepthCameraTag >
 TODO(louise) Substitute with sdf::DepthCamera once that exists? This is currently the whole <sensor> element. More...
 
using Geometry = Component< sdf::Geometry, class GeometryTag >
 This component holds an entity's geometry. More...
 
using GpuLidar = Component< sdf::ElementPtr, class GpuLidarTag >
 TODO(louise) Substitute with sdf::GpuLidar once that exists? This is currently the whole <sensor> element. More...
 
using Gravity = Component< math::Vector3d, class GravityTag >
 Store the gravity acceleration. More...
 
using Imu = Component< sdf::ElementPtr, class ImuTag >
 TODO(anyone) Substitute with sdf::Imu once that exists? This is currently the whole <sensor> element. More...
 
using Inertial = Component< ignition::math::Inertiald, class InertialTag >
 A component type that contains inertial, ignition::math::Inertiald, information. 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 >
 A component that contains the joint axis . This is a simple wrapper around sdf::JointAxis. More...
 
using JointType = Component< sdf::JointType, class JointTypeTag >
 A component that contains the joint type. This is a simple wrapper around sdf::JointType. More...
 
using JointVelocity = Component< double, class JointVelocityTag >
 Velocity of a joint's first axis in SI units (rad/s for revolute, m/s for prismatic). 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 LevelEntityNamesBase = Component< std::set< std::string >, class LevelEntityNamesTag >
 A derived class LevelEntityNames is used below so that the *Serialize functions can be overridden. An alternative would be to create custom stream operators. More...
 
using Light = Component< sdf::Light, class LightTag >
 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 ignition::math::Vector3d. More...
 
using LinearVelocity = Component< math::Vector3d, class LinearVelocityTag >
 A component type that contains linear velocity of an entity represented by ignition::math::Vector3d. More...
 
using Link = Component< NoData, class LinkTag >
 A component that identifies an entity as being a link. 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 MagneticField = Component< math::Vector3d, class MagneticFieldTag >
 Stores the 3D magnetic field in teslas. More...
 
using Magnetometer = Component< sdf::ElementPtr, class MagnetometerTag >
 TODO(anyone) Substitute with sdf::Magnetometer once that exists? This is currently the whole <sensor> element. More...
 
using Material = Component< sdf::Material, class MaterialTag >
 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 Pose = Component< ignition::math::Pose3d, class PoseTag >
 A component type that contains pose, ignition::math::Pose3d, information. More...
 
using Sensor = Component< NoData, class SensorTag >
 A component that identifies an entity as being a link. More...
 
using Static = Component< bool, class StaticTag >
 A component used to indicate that a model is static (i.e. not moveable). More...
 
using ThreadPitch = Component< double, class ThreadPitchTag >
 A component used to store the thread pitch of a screw joint. More...
 
using Visual = Component< NoData, class VisualTag >
 A component that identifies an entity as being a visual. More...
 
using World = Component< NoData, class WorldTag >
 A component that identifies an entity as being a world. More...
 

Functions

 IGN_GAZEBO_REGISTER_COMPONENT ("ign_gazebo_components.JointVelocity", JointVelocity) using JointVelocity2
 Velocity of a joint's second axis in SI units (rad/s for revolute, m/s for prismatic). 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.AngularVelocity", AngularVelocity) using WorldAngularVelocity = Component<sdf::JointAxis, class JointAxis2Tag>
 A component type that contains angular velocity of an entity in the world frame represented by ignition::math::Vector3d. 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

◆ Altimeter

using Altimeter = Component<sdf::ElementPtr, class AltimeterTag>

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

◆ AngularVelocity

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

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

◆ Camera

using Camera = Component<sdf::ElementPtr, class CameraTag>

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

◆ CanonicalLink

using CanonicalLink = Component<NoData, class CanonicalLinkTag>

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

◆ ChildLinkName

using ChildLinkName = Component<std::string, class ChildLinkNameTag>

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

◆ Collision

using Collision = Component<NoData, class CollisionTag>

A component that identifies an entity as being a collision.

◆ ContactSensor

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

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

◆ ContactSensorData

using ContactSensorData = Component<msgs::Contacts, class ContactSensorDataTag>

A component type that contains a list of contacts.

◆ DepthCamera

using DepthCamera = Component<sdf::ElementPtr, class DepthCameraTag>

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

◆ Geometry

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

This component holds an entity's geometry.

◆ GpuLidar

using GpuLidar = Component<sdf::ElementPtr, class GpuLidarTag>

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

◆ Gravity

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

Store the gravity acceleration.

◆ Imu

using Imu = Component<sdf::ElementPtr, class ImuTag>

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

◆ Inertial

using Inertial = Component<ignition::math::Inertiald, class InertialTag>

A component type that contains inertial, ignition::math::Inertiald, information.

◆ Joint

using Joint = Component<NoData, class JointTag>

A component that identifies an entity as being a joint.

◆ JointAxis

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

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

◆ JointType

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

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

◆ JointVelocity

using JointVelocity = Component<double, class JointVelocityTag>

Velocity of a joint's first axis in SI units (rad/s for revolute, m/s for prismatic).

◆ Level

using Level = Component<NoData, class LevelTag>

This component identifies an entity as being a level.

◆ LevelBuffer

using LevelBuffer = Component<double, class LevelBufferTag>

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

◆ LevelEntityNamesBase

using LevelEntityNamesBase = Component<std::set<std::string>, class LevelEntityNamesTag>

A derived class LevelEntityNames is used below so that the *Serialize functions can be overridden. An alternative would be to create custom stream operators.

◆ Light

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

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 ignition::math::Vector3d.

◆ LinearVelocity

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

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

◆ Link

using Link = Component<NoData, class LinkTag>

A component that identifies an entity as being a link.

◆ LogicalCamera

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

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

◆ MagneticField

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

Stores the 3D magnetic field in teslas.

◆ Magnetometer

using Magnetometer = Component<sdf::ElementPtr, class MagnetometerTag>

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

◆ Material

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

This component holds an entity's material.

◆ Model

using Model = Component<NoData, class ModelTag>

A component that identifies an entity as being a model.

◆ Name

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 gazebo::SdfEntityCreator class.

◆ ParentLinkName

using ParentLinkName = Component<std::string, class ParentLinkNameTag>

Holds the name of the entity's parent link.

◆ Performer

using Performer = Component<NoData, class PerformerTag>

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.

◆ Pose

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

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

◆ Sensor

using Sensor = Component<NoData, class SensorTag>

A component that identifies an entity as being a link.

◆ Static

using Static = Component<bool, class StaticTag>

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

◆ ThreadPitch

using ThreadPitch = Component<double, class ThreadPitchTag>

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

◆ Visual

using Visual = Component<NoData, class VisualTag>

A component that identifies an entity as being a visual.

◆ World

using World = Component<NoData, class WorldTag>

A component that identifies an entity as being a world.

Function Documentation

◆ IGN_GAZEBO_REGISTER_COMPONENT() [1/3]

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

Velocity of a joint's second axis in SI units (rad/s for revolute, m/s for prismatic).

◆ IGN_GAZEBO_REGISTER_COMPONENT() [2/3]

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() [3/3]

IGN_GAZEBO_REGISTER_COMPONENT ( "ign_gazebo_components.AngularVelocity"  ,
AngularVelocity   
) = Component<sdf::JointAxis, class JointAxis2Tag>

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

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

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

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

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

Referenced by LevelEntityNames::Deserialize().