Gazebo Sim

API Reference

7.7.0
gz::sim Namespace Reference

Gazebo is a leading open source robotics simulator, that provides high fidelity physics, rendering, and sensor simulation. More...

Namespaces

 comms
 
 components
 Components represent data, such as position information. An Entity usually has one or more associated components.
 
 events
 Namespace for all events. Refer to the EventManager class for more information about events.
 
 gui
 
 GZ_SIM_VERSION_NAMESPACE
 
 inspector
 
 logical_audio
 
 serializers
 A Serializer class is used to serialize and deserialize a component. It is passed in as the third template parameter to components::Component. Eg.
 
 systems
 Namespace for all System plugins. Refer to the System class for more information about systems.
 
 traits
 

Classes

class  Actor
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a actor entity. More...
 
class  AirPressure
 A class that handles air pressure changes. More...
 
class  AlignTool
 Provides buttons for the align tool. More...
 
class  Altimeter
 A class that handles altimeter changes. More...
 
class  AnimationUpdateData
 Data structure for updating skeleton animations. More...
 
class  ApplyForceTorque
 Publish wrench to "/world/<world_name>/wrench" topic. Automatically loads the ApplyLinkWrench system. More...
 
class  BananaForScale
 Provides buttons for adding a banana for scale. More...
 
class  CopyPaste
 Plugin for copying/pasting entities in the GUI. More...
 
struct  Display
 Data used by the DisplayData() function to filter and sort the resources to be displayed. More...
 
class  EntityComponentManager
 The EntityComponentManager constructs, deletes, and returns components and entities. A component can be of any class which inherits from components::BaseComponent. More...
 
class  EntityContextMenu
 This plugin is in charge of showing the entity context menu when the right button is clicked on a visual. More...
 
class  EntityContextMenuHandler
 
class  EntityContextMenuItem
 A QQUickItem that manages the render window. More...
 
class  EntityTree
 Displays a tree view with all the entities in the world. More...
 
class  EnvironmentalSensorSystem
 Sensor for reading environmental data loaded from outside world. To use, add this system to the world file, then instantiate sensors of custom type with gz:type="environmental_sensor/{field_name}", where field_name refers to the type of data you would like to output. Alternatively, if you would like to specify a custom field name you may do so using the <environment_variable> tag. More...
 
class  EnvironmentLoader
 A GUI plugin for a user to load an Environment component into the ECM on a live simulation. More...
 
class  EnvironmentVisualization
 A GUI plugin for a user to load an Environment component into the ECM on a live simulation. More...
 
class  EnvironmentVisualizationTool
 This class helps handle point cloud visuallizations of environment data. More...
 
class  EventManager
 The EventManager is used to send/receive notifications of simulator events. More...
 
class  GuiSystem
 Base class for a GUI System. More...
 
class  GzSceneManager
 Updates a 3D scene based on information coming from the ECM. This plugin doesn't instantiate a new 3D scene. Instead, it relies on another plugin being loaded alongside it that will create and paint the scene to the window, such as gz::gui::plugins::MinimalScene. More...
 
class  GzSimPlugin
 GzSim QML Plugin that registers C++ class so that they are accessible from QML. More...
 
class  Imu
 A class that handles IMU sensor changes. More...
 
class  ISystemConfigure
 Interface for a system that implements optional configuration. More...
 
class  ISystemConfigureParameters
 Interface for a system that declares parameters. More...
 
class  ISystemPostUpdate
 Interface for a system that uses the PostUpdate phase. More...
 
class  ISystemPreUpdate
 Interface for a system that uses the PreUpdate phase. More...
 
class  ISystemReset
 
class  ISystemUpdate
 Interface for a system that uses the Update phase. More...
 
class  Joint
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a joint entity. More...
 
class  JointType
 A class that handles joint changes. More...
 
class  Lidar
 A class that handles Lidar sensor changes. More...
 
class  Light
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a light entity. More...
 
class  Lights
 Provides buttons for adding a point, directional, or spot light to the scene. More...
 
class  Link
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a link entity. More...
 
class  Magnetometer
 A class that handles magnetometer changes. More...
 
class  MarkerManager
 Creates, deletes, and maintains marker visuals. Only the Scene class should instantiate and use this class. More...
 
class  Model
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a model entity. More...
 
class  ModelEditor
 Model Editor. More...
 
class  MouseDrag
 Translate and rotate links by dragging them with the mouse. Automatically loads the ApplyLinkWrench system. More...
 
class  PathModel
 Provides a model by which the resource spawner qml plugin pulls and updates from. More...
 
class  PlaybackScrubber
 Provides slider and functionality for log playback. to the scene. More...
 
class  PlotComponent
 A container of the component data that keeps track of the registered attributes and update their values and their registered charts. More...
 
class  Plotting
 Physics data plotting handler that keeps track of the registered components, update them and update the plot. More...
 
class  Pose3d
 A class that handles Pose3d changes. More...
 
class  RenderUtil
 
struct  Resource
 Resource used to update the ResourceModel. More...
 
class  ResourceModel
 Provides a model by which the resource spawner qml plugin pulls and updates from. More...
 
class  ResourceSpawner
 Provides interface for communicating to backend for generation of local models. More...
 
class  SceneManager
 Scene manager class for loading and managing objects in the scene. More...
 
class  SdfEntityCreator
 Provides convenient functions to spawn entities and load their plugins from SDF elements, to remove them, and to change their hierarchy. More...
 
class  Sensor
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a sensor entity. More...
 
class  Server
 The server instantiates and controls simulation. More...
 
class  ServerConfig
 Configuration parameters for a Server. An instance of this object can be used to construct a Server with a particular configuration. More...
 
class  Shapes
 Provides buttons for adding a box, sphere, or cylinder to the scene. More...
 
class  Spawn
 Allows to spawn models and lights using the spawn gui events or drag and drop. More...
 
class  System
 Base class for a System. More...
 
class  SystemLoader
 Class for loading/unloading System plugins. More...
 
class  TestFixture
 Helper class to write automated tests. It provides a convenient API to load a world file, step simulation and check entities and components. More...
 
class  TransformControl
 Provides buttons for translation, rotation, and scale. More...
 
class  TreeModel
 TODO. More...
 
struct  UpdateInfo
 Information passed to systems on the update callback. More...
 
class  VideoRecorder
 Provides video recording cababilities to the 3D scene. More...
 
class  ViewAngle
 Provides buttons for viewing angles. More...
 
class  VisualizationCapabilities
 Allows to visualize transparent, collisions, inertial, CoM and more. More...
 
class  VisualizeContacts
 Visualize the contacts returned by the Physics plugin. Use the checkbox to turn visualization on or off and spin boxes to change the size of the markers. More...
 
class  VisualizeLidar
 Visualize the LaserScan message returned by the sensors. Use the checkbox to turn visualization of non-hitting rays on or off and the textfield to select the message to be visualised. The combobox is used to select the type of visual for the sensor data. More...
 
class  World
 This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a world entity. More...
 

Typedefs

using ComponentCreator = std::function< void(EntityComponentManager &, Entity, QStandardItem *)>
 
using ComponentTypeId = uint64_t
 A unique identifier for a component type. A component type must be derived from components::BaseComponent and can contain plain data or something more complex like gz::math::Pose3d. More...
 
using Entity = uint64_t
 An Entity identifies a single object in simulation such as a model, link, or light. At its core, an Entity is just an identifier. More...
 
using EntityGraph = math::graph::DirectedGraph< Entity, bool >
 Type alias for the graph that holds entities. Each vertex is an entity, and the direction points from the parent to its children. All edges are positive booleans. More...
 
using EntityQueryCallback = std::function< void(const UpdateInfo, EntityComponentManager &)>
 typedef for query callbacks More...
 
using SystemPluginPtr = gz::plugin::SpecializedPluginPtr< System, ISystemConfigure, ISystemPreUpdate, ISystemUpdate, ISystemPostUpdate >
 
using UpdateCallback = std::function< void(EntityComponentManager &)>
 UpdateCallback is a function defition that is used by a component to manage ECM changes. More...
 

Enumerations

enum  AlignAxis { ALIGN_X = 0, ALIGN_Y = 1, ALIGN_Z = 2 }
 Enumeration of the axes to be aligned relative to. More...
 
enum  AlignConfig { ALIGN_MIN, ALIGN_MID, ALIGN_MAX }
 
enum  AlignState { HOVER = 0, RESET = 1, ALIGN = 2, NONE = 3 }
 Enumeration of the states within the Align Tool. More...
 
enum  ComponentState { NoChange = 0, PeriodicChange = 1, OneTimeChange = 2 }
 Possible states for a component. More...
 
enum  PrimitiveLight { kDirectional, kPoint, kSpot }
 Enumeration of available primitive light types. More...
 
enum  PrimitiveShape {
  kBox, kCapsule, kCylinder, kEllipsoid,
  kSphere
}
 Enumeration of available primitive shape types. More...
 
enum  TransformType { ADD_VELOCITY_LOCAL, ADD_VELOCITY_GLOBAL, LOCAL, GLOBAL }
 Transform Type. More...
 

Functions

void addResourcePaths (const std::vector< std::string > &_paths={})
 Add resource paths based on latest environment variables. This will update the SDF and Gazebo environment variables, and optionally add more paths to the list. More...
 
std::string asFullPath (const std::string &_uri, const std::string &_filePath)
 Combine a URI and a file path into a full path. If the URI is already a full path or contains a scheme, it won't be modified. If the URI is a relative path, the file path will be prepended. More...
 
template<class Out >
Out convert (const math::AxisAlignedBox &_in)
 Generic conversion from axis aligned box object to another type. More...
 
template<>
msgs::AxisAlignedBox convert (const math::AxisAlignedBox &_in)
 Specialized conversion from a math axis aligned box object to an axis aligned box message. More...
 
template<class Out >
Out convert (const math::Inertiald &_in)
 Generic conversion from a math inertial to another type. More...
 
template<>
msgs::Inertial convert (const math::Inertiald &_in)
 Specialized conversion from a math inertial to an inertial message. More...
 
template<class Out >
Out convert (const msgs::Actor &_in)
 Generic conversion from an actor message to another type. More...
 
template<>
sdf::Actor convert (const msgs::Actor &_in)
 Specialized conversion from an actor message to an actor SDF object. More...
 
template<class Out >
Out convert (const msgs::Atmosphere &_in)
 Generic conversion from an atmosphere message to another type. More...
 
template<>
sdf::Atmosphere convert (const msgs::Atmosphere &_in)
 Specialized conversion from an atmosphere message to an atmosphere SDF object. More...
 
template<class Out >
Out convert (const msgs::Axis &_in)
 Generic conversion from an axis message to another type. More...
 
template<>
sdf::JointAxis convert (const msgs::Axis &_in)
 Specialized conversion from an axis message to a joint axis SDF object. More...
 
template<class Out >
Out convert (const msgs::AxisAlignedBox &_in)
 Generic conversion from an axis aligned box message to another type. More...
 
template<>
math::AxisAlignedBox convert (const msgs::AxisAlignedBox &_in)
 Specialized conversion from an math axis aligned box message to an axis aligned box object. More...
 
template<class Out >
Out convert (const msgs::Collision &_in)
 Generic conversion from a collision message to another type. More...
 
template<>
sdf::Collision convert (const msgs::Collision &_in)
 Specialized conversion from a collision message to a collision SDF object. More...
 
template<class Out >
Out convert (const msgs::Geometry &_in)
 Generic conversion from a geometry message to another type. More...
 
template<>
sdf::Geometry convert (const msgs::Geometry &_in)
 Specialized conversion from a geometry message to a geometry SDF object. More...
 
template<class Out >
Out convert (const msgs::Inertial &_in)
 Generic conversion from an inertial message to another type. More...
 
template<>
math::Inertiald convert (const msgs::Inertial &_in)
 Specialized conversion from an inertial message to an inertial math object. More...
 
template<class Out >
Out convert (const msgs::Light &_in)
 Generic conversion from a light message to another type. More...
 
template<>
sdf::Light convert (const msgs::Light &_in)
 Specialized conversion from a light message to a light SDF object. More...
 
template<class Out >
Out convert (const msgs::Material &_in)
 Generic conversion from a material message to another type. More...
 
template<>
sdf::Material convert (const msgs::Material &_in)
 Specialized conversion from a material message to a material SDF object. More...
 
template<class Out >
Out convert (const msgs::ParticleEmitter &)
 Generic conversion from a particle emitter SDF object to another type. More...
 
template<>
sdf::ParticleEmitter convert (const msgs::ParticleEmitter &_in)
 Specialized conversion from a particle emitter SDF object to a particle emitter message object. More...
 
template<class Out >
Out convert (const msgs::Physics &_in)
 Generic conversion from a physics message to another type. More...
 
template<>
sdf::Physics convert (const msgs::Physics &_in)
 Specialized conversion from a physics message to a physics SDF object. More...
 
template<class Out >
Out convert (const msgs::Plugin &)
 Generic conversion from a msgs::Plugin to another type. More...
 
template<>
sdf::Plugin convert (const msgs::Plugin &_in)
 Specialized conversion from a msgs::Plugin to an sdf::Plugin. More...
 
template<class Out >
Out convert (const msgs::Plugin_V &)
 Generic conversion from a msgs::Plugin_V to another type. More...
 
template<>
sdf::Plugins convert (const msgs::Plugin_V &_in)
 Specialized conversion from a msgs::Plugin_V to an sdf::Plugins. More...
 
template<class Out >
Out convert (const msgs::Pose &_in)
 Generic conversion from a msgs Pose to another type. More...
 
template<>
math::Pose3d convert (const msgs::Pose &_in)
 Specialized conversion for msgs Pose to math Pose. More...
 
template<class Out >
Out convert (const msgs::Projector &)
 Generic conversion from a projector SDF object to another type. More...
 
template<>
sdf::Projector convert (const msgs::Projector &_in)
 Specialized conversion from a projector SDF object to a projector message object. More...
 
template<class Out >
Out convert (const msgs::Scene &_in)
 Generic conversion from a scene message to another type. More...
 
template<>
sdf::Scene convert (const msgs::Scene &_in)
 Specialized conversion from a scene message to a scene SDF object. More...
 
template<class Out >
Out convert (const msgs::Sensor &_in)
 Generic conversion from a sensor message to another type. More...
 
template<>
sdf::Sensor convert (const msgs::Sensor &_in)
 Specialized conversion from a sensor message to a sensor SDF object. More...
 
template<class Out >
Out convert (const msgs::SensorNoise &_in)
 Generic conversion from a sensor noise message to another type. More...
 
template<>
sdf::Noise convert (const msgs::SensorNoise &_in)
 Specialized conversion from a sensor noise message to a noise SDF object. More...
 
template<class Out >
Out convert (const msgs::Time &_in)
 Generic conversion from a time message to another type. More...
 
template<>
std::chrono::steady_clock::duration convert (const msgs::Time &_in)
 Specialized conversion from a time message to a steady clock duration. More...
 
template<class Out >
Out convert (const msgs::WorldStatistics &_in)
 Generic conversion from a world statistics message to another type. More...
 
template<>
UpdateInfo convert (const msgs::WorldStatistics &_in)
 Specialized conversion from a world statistics message to an UpdateInfo object. More...
 
template<class Out >
Out convert (const sdf::Actor &_in)
 Generic conversion from an SDF actor to another type. More...
 
template<>
msgs::Actor convert (const sdf::Actor &_in)
 Specialized conversion from an SDF actor to an actor message. More...
 
template<class Out >
Out convert (const sdf::Atmosphere &_in)
 Generic conversion from an SDF atmosphere to another type. More...
 
template<>
msgs::Atmosphere convert (const sdf::Atmosphere &_in)
 Specialized conversion from an SDF atmosphere to an atmosphere message. More...
 
template<class Out >
Out convert (const sdf::Collision &_in)
 Generic conversion from an SDF collision to another type. More...
 
template<>
msgs::Collision convert (const sdf::Collision &_in)
 Specialized conversion from an SDF collision to a collision message. More...
 
template<class Out >
Out convert (const sdf::Element &)
 Generic conversion from an SDF element to another type. More...
 
template<>
msgs::Plugin convert (const sdf::Element &_in)
 Specialized conversion from an SDF element to a plugin message. More...
 
template<class Out >
Out convert (const sdf::Geometry &_in)
 Generic conversion from an SDF geometry to another type. More...
 
template<>
msgs::Geometry convert (const sdf::Geometry &_in)
 Specialized conversion from an SDF geometry to a geometry message. More...
 
template<class Out >
Out convert (const sdf::Gui &_in)
 Generic conversion from an SDF gui to another type. More...
 
template<>
msgs::GUI convert (const sdf::Gui &_in)
 Specialized conversion from an SDF gui to a gui message. More...
 
template<class Out >
Out convert (const sdf::JointAxis &_in)
 Generic conversion from an SDF joint axis to another type. More...
 
template<>
msgs::Axis convert (const sdf::JointAxis &_in)
 Specialized conversion from an SDF joint axis to an axis message. More...
 
template<class Out >
Out convert (const sdf::Light &_in)
 Generic conversion from an SDF light to another type. More...
 
template<>
msgs::Light convert (const sdf::Light &_in)
 Specialized conversion from an SDF light to a light message. More...
 
std::string convert (const sdf::LightType &_in)
 Generic conversion from a SDF light type to string. More...
 
template<class Out >
Out convert (const sdf::Material &_in)
 Generic conversion from an SDF material to another type. More...
 
template<>
msgs::Material convert (const sdf::Material &_in)
 Specialized conversion from an SDF material to a material message. More...
 
template<class Out >
Out convert (const sdf::ParticleEmitter &)
 Generic conversion from a particle emitter SDF object to another type. More...
 
template<>
msgs::ParticleEmitter convert (const sdf::ParticleEmitter &_in)
 Specialized conversion from a particle emitter SDF object to a particle emitter message object. More...
 
template<class Out >
Out convert (const sdf::Physics &_in)
 Generic conversion from an SDF Physics to another type. More...
 
template<>
msgs::Physics convert (const sdf::Physics &_in)
 Specialized conversion from an SDF physics to a physics message. More...
 
template<class Out >
Out convert (const sdf::Plugin &)
 Generic conversion from an SDF plugin to another type. More...
 
template<>
msgs::Plugin convert (const sdf::Plugin &_in)
 Specialized conversion from an SDF plugin to a plugin message. More...
 
template<class Out >
Out convert (const sdf::Plugins &)
 Generic conversion from an SDF plugins to another type. More...
 
template<>
msgs::Plugin_V convert (const sdf::Plugins &_in)
 Specialized conversion from an SDF plugins to a plugin_v message. More...
 
template<class Out >
Out convert (const sdf::Projector &)
 Generic conversion from a projector SDF object to another type. More...
 
template<>
msgs::Projector convert (const sdf::Projector &_in)
 Specialized conversion from a projector SDF object to a projector message object. More...
 
template<class Out >
Out convert (const sdf::Scene &_in)
 Generic conversion from an SDF scene to another type. More...
 
template<>
msgs::Scene convert (const sdf::Scene &_in)
 Specialized conversion from an SDF scene to a scene message. More...
 
template<class Out >
Out convert (const sdf::Sensor &_in)
 Generic conversion from an SDF Sensor to another type. More...
 
template<>
msgs::Sensor convert (const sdf::Sensor &_in)
 Specialized conversion from an SDF sensor to a sensor message. More...
 
template<class Out >
Out convert (const std::chrono::steady_clock::duration &_in)
 Generic conversion from a steady clock duration to another type. More...
 
template<>
msgs::Time convert (const std::chrono::steady_clock::duration &_in)
 Specialized conversion from a steady clock duration to a time message. More...
 
sdf::LightType convert (const std::string &_in)
 Specialized conversion from a string to a sdf light type. More...
 
template<class Out >
Out convert (const UpdateInfo &_in)
 Generic conversion from update info to another type. More...
 
template<>
msgs::WorldStatistics convert (const UpdateInfo &_in)
 Specialized conversion from update info to a world statistics message. More...
 
template<class ComponentType >
bool enableComponent (EntityComponentManager &_ecm, Entity _entity, bool _enable=true)
 Helper function to "enable" a component (i.e. create it if it doesn't exist) or "disable" a component (i.e. remove it if it exists). More...
 
std::unordered_set< EntityentitiesFromScopedName (const std::string &_scopedName, const EntityComponentManager &_ecm, Entity _relativeTo=kNullEntity, const std::string &_delim="::")
 Helper function to get an entity given its scoped name. The scope may start at any level by default. For example, in this hierarchy: More...
 
Entity entityFromMsg (const EntityComponentManager &_ecm, const msgs::Entity &_msg)
 Helper function to get an entity from an entity message. The returned entity is not guaranteed to exist. More...
 
ComponentTypeId entityTypeId (const Entity &_entity, const EntityComponentManager &_ecm)
 Generally, each entity will be of some specific high-level type, such as World, Sensor, Collision, etc, and one type only. The entity type is usually marked by having some component that represents that type, such as components::Visual. More...
 
std::string entityTypeStr (const Entity &_entity, const EntityComponentManager &_ecm)
 Generally, each entity will be of some specific high-level type, such as "world", "sensor", "collision", etc, and one type only. More...
 
std::optional< math::Vector3dgetGridFieldCoordinates (const EntityComponentManager &_ecm, const math::Vector3d &_worldPosition, const std::shared_ptr< components::EnvironmentalData > &_gridField)
 Get grid field coordinates based on a world position in cartesian coordinate frames. More...
 
std::string getGUIConfigPath ()
 getGUIConfigPath return the GUI config path More...
 
std::string getGUIPluginInstallDir ()
 getGUIPluginInstallDir return the GUI plugin install dir More...
 
std::string getInstallPrefix ()
 getInstallPrefix return the install prefix of the library i.e. CMAKE_INSTALL_PREFIX unless the library has been moved More...
 
std::string getMediaInstallDir ()
 getMediaInstallDir return the media install dir More...
 
std::string getPluginInstallDir ()
 getPluginInstallDir return the plugin install dir More...
 
std::string getPrimitive (const std::string &_typeName)
 Return an SDF string of one of the available primitive shape or light types. More...
 
std::string getPrimitiveLight (const PrimitiveLight &_type)
 Return an SDF string of one of the available primitive light types. More...
 
std::string getPrimitiveShape (const PrimitiveShape &_type)
 Return an SDF string of one of the available primitive shape types. More...
 
std::string getServerConfigPath ()
 getServerConfigPath return the server config path More...
 
std::string getSystemConfigPath ()
 getSystemConfigPath return the system config path More...
 
std::optional< TransformTypegetTransformType (const std::string &_str)
 Given a string return the type of transform. More...
 
std::string getWorldInstallDir ()
 getWorldInstallDir return the world install dir More...
 
const common::MeshloadMesh (const sdf::Mesh &_meshSdf)
 Load a mesh from a Mesh SDF DOM. More...
 
std::list< ServerConfig::PluginInfoloadPluginInfo (bool _isPlayback=false)
 Load plugin information, following ordering. More...
 
std::list< ServerConfig::PluginInfoparsePluginsFromFile (const std::string &_fname)
 Parse plugins from XML configuration file. More...
 
std::list< ServerConfig::PluginInfoparsePluginsFromString (const std::string &_str)
 Parse plugins from XML configuration string. More...
 
math::Vector3d relativeVel (const Entity &_entity, const EntityComponentManager &_ecm)
 Helper function to compute world velocity of an entity. More...
 
std::string removeParentScope (const std::string &_name, const std::string &_delim)
 Helper function to remove a parent scope from a given name. This removes the first name found before the delimiter. More...
 
std::string resolveSdfWorldFile (const std::string &_sdfFilename, const std::string &_fuelResourceCache="")
 Convert an SDF world filename string, such as "shapes.sdf", to full system file path. The provided SDF filename may be a Fuel URI, relative path, name of an installed Gazebo world filename, or an absolute path. More...
 
std::vector< std::stringresourcePaths ()
 Get resource paths based on latest environment variables. More...
 
std::string scopedName (const Entity &_entity, const EntityComponentManager &_ecm, const std::string &_delim="/", bool _includePrefix=true)
 Helper function to generate scoped name for an entity. More...
 
void set (msgs::SensorNoise *_msg, const sdf::Noise &_sdf)
 Helper function that sets a mutable msgs::SensorNoise object to the values contained in a sdf::Noise object. More...
 
void set (msgs::Time *_msg, const std::chrono::steady_clock::duration &_in)
 Helper function that sets a mutable msgs::Time object to the values contained in a std::chrono::steady_clock::duration object. More...
 
void set (msgs::WorldStatistics *_msg, const UpdateInfo &_in)
 Helper function that sets a mutable msgs::WorldStatistics object to the values contained in a sim::UpdateInfo object. More...
 
void setNoise (sdf::Noise &_noise, double _mean, double _meanBias, double _stdDev, double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime)
 Helper function that will set all noise properties. More...
 
std::optional< math::Vector3dsphericalCoordinates (Entity _entity, const EntityComponentManager &_ecm)
 Get the spherical coordinates for an entity. More...
 
std::string topicFromScopedName (const Entity &_entity, const EntityComponentManager &_ecm, bool _excludeWorld=true)
 Helper function that returns a valid Gazebo Transport topic consisting of the scoped name for the provided entity. More...
 
Entity topLevelModel (const Entity &_entity, const EntityComponentManager &_ecm)
 Get the top level model of an entity. More...
 
math::Vector3d transformFrame (const TransformType _type, const math::Pose3d &_pose, const math::Vector3d &_velocity, const math::Vector3d &_reading)
 Given a string return the type of transform. More...
 
std::string validTopic (const std::vector< std::string > &_topics)
 Helper function to generate a valid transport topic, given a list of topics ordered by preference. The generated topic will be, in this order: More...
 
Entity worldEntity (const Entity &_entity, const EntityComponentManager &_ecm)
 Get the world to which the given entity belongs. More...
 
Entity worldEntity (const EntityComponentManager &_ecm)
 Get the first world entity that's found. More...
 
math::Pose3d worldPose (const Entity &_entity, const EntityComponentManager &_ecm)
 Helper function to compute world pose of an entity. More...
 

Variables

class GZ_SIM_HIDDEN EntityComponentManagerPrivate
 
class GZ_SIM_HIDDEN EventManagerPrivate
 
static const ComponentTypeId kComponentTypeIdInvalid = UINT64_MAX
 Id that indicates an invalid component type. More...
 
const Entity kNullEntity {0}
 Indicates a non-existant or invalid Entity. More...
 
const std::string kRenderPluginPathEnv {"GZ_SIM_RENDER_ENGINE_PATH"}
 Environment variable holding paths to custom rendering engine plugins. More...
 
const std::string kRenderPluginPathEnvDeprecated
 
const std::string kResourcePathEnv {"GZ_SIM_RESOURCE_PATH"}
 Environment variable holding resource paths. More...
 
const std::string kResourcePathEnvDeprecated {"IGN_GAZEBO_RESOURCE_PATH"}
 
const std::string kSdfPathEnv {"SDF_PATH"}
 Environment variable used by SDFormat to find URIs inside <include> More...
 
const std::string kServerConfigPathEnv {"GZ_SIM_SERVER_CONFIG_PATH"}
 Environment variable holding server config paths. More...
 
class GZ_SIM_HIDDEN LinkPrivate
 
class GZ_SIM_HIDDEN ModelPrivate
 
class GZ_SIM_HIDDEN SystemLoaderPrivate
 
class GZ_SIM_HIDDEN TestFixturePrivate
 
class GZ_SIM_HIDDEN WorldPrivate
 

Detailed Description

Gazebo is a leading open source robotics simulator, that provides high fidelity physics, rendering, and sensor simulation.

Typedef Documentation

◆ ComponentCreator

using ComponentCreator = std::function<void(EntityComponentManager &, Entity, QStandardItem *)>

ComponentCreator is a function definition that a component can use to create the appropriate UI elements for an Entity based on a ComponentTypeId.

See also
void ComponentInspectorEditor::RegisterComponentCreator( UpdateCallback _cb)

◆ ComponentTypeId

using ComponentTypeId = uint64_t

A unique identifier for a component type. A component type must be derived from components::BaseComponent and can contain plain data or something more complex like gz::math::Pose3d.

◆ Entity

using Entity = uint64_t

An Entity identifies a single object in simulation such as a model, link, or light. At its core, an Entity is just an identifier.

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

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.

An Entity that needs to be identified and used by Systems should be created through the EntityComponentManager.

◆ EntityGraph

Type alias for the graph that holds entities. Each vertex is an entity, and the direction points from the parent to its children. All edges are positive booleans.

◆ EntityQueryCallback

typedef for query callbacks

◆ SystemPluginPtr

◆ UpdateCallback

UpdateCallback is a function defition that is used by a component to manage ECM changes.

See also
void ComponentInspectorEditor::AddUpdateCallback(UpdateCallback _cb)

Enumeration Type Documentation

◆ AlignAxis

enum AlignAxis
strong

Enumeration of the axes to be aligned relative to.

Enumerator
ALIGN_X 

Indicates an alignment relative to the x axis.

ALIGN_Y 

Indicates an alignment relative to the y axis.

ALIGN_Z 

Indicates an alignment relative to the z axis.

◆ AlignConfig

enum AlignConfig
strong
Enumerator
ALIGN_MIN 
ALIGN_MID 
ALIGN_MAX 

◆ AlignState

enum AlignState
strong

Enumeration of the states within the Align Tool.

Enumerator
HOVER 

Indicates the user is currently hovering the mouse over an align button.

RESET 

Indicates a reset of the currently placed nodes, only occurs on a hover exit if the align button has not been clicked.

ALIGN 

Indicates the user has clicked the align button.

NONE 

Indicates the user is currently not utilizing the align tool.

◆ ComponentState

enum ComponentState
strong

Possible states for a component.

Enumerator
NoChange 

Component value has not changed.

PeriodicChange 

Component value has changed, and is changing periodically. This indicates to systems that it is ok to drop a few samples.

OneTimeChange 

Component value has suffered a one-time change. This indicates to systems that this change must be processed and can't be dropped.

◆ PrimitiveLight

enum PrimitiveLight
strong

Enumeration of available primitive light types.

Enumerator
kDirectional 
kPoint 
kSpot 

◆ PrimitiveShape

enum PrimitiveShape
strong

Enumeration of available primitive shape types.

Enumerator
kBox 
kCapsule 
kCylinder 
kEllipsoid 
kSphere 

◆ TransformType

Transform Type.

Enumerator
ADD_VELOCITY_LOCAL 

Add the sensor's velocity and retrieve the value after transforming the vector to the local frame. (Example would be for a wind speed sensor or current sensor).

ADD_VELOCITY_GLOBAL 

Add the sensor's velocity and retrieve the value in a global frame. (For instance to get Airspeed in a global frame)

LOCAL 

The vector doesn't change with speed but we want it in local frame. Example could be magnetic field lines in local frame.

GLOBAL 

The vector doesn't change with speed but we want it in local frame. Example could be magnetic field lines in global frame.

Function Documentation

◆ addResourcePaths()

void gz::sim::addResourcePaths ( const std::vector< std::string > &  _paths = {})

Add resource paths based on latest environment variables. This will update the SDF and Gazebo environment variables, and optionally add more paths to the list.

Parameters
[in]_pathsOptional paths to add.

◆ asFullPath()

std::string gz::sim::asFullPath ( const std::string _uri,
const std::string _filePath 
)

Combine a URI and a file path into a full path. If the URI is already a full path or contains a scheme, it won't be modified. If the URI is a relative path, the file path will be prepended.

Parameters
[in]_uriURI, which can have a scheme, or be full or relative paths.
[in]_filePathThe path to a file in disk.
Returns
The full path URI.

◆ convert() [1/82]

Out gz::sim::convert ( const math::AxisAlignedBox _in)

Generic conversion from axis aligned box object to another type.

Specialized conversion from a math axis aligned box object to an axis aligned box message.

Parameters
[in]_inAxis aligned box object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [2/82]

msgs::AxisAlignedBox gz::sim::convert ( const math::AxisAlignedBox _in)

Specialized conversion from a math axis aligned box object to an axis aligned box message.

Parameters
[in]_inAxis aligned box message
Returns
Axis aligned box message.

Specialized conversion from a math axis aligned box object to an axis aligned box message.

Parameters
[in]_inAxis aligned box object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [3/82]

Out gz::sim::convert ( const math::Inertiald _in)

Generic conversion from a math inertial to another type.

Specialized conversion from a math inertial to an inertial message.

Parameters
[in]_inMath inertial.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [4/82]

msgs::Inertial gz::sim::convert ( const math::Inertiald _in)

Specialized conversion from a math inertial to an inertial message.

Parameters
[in]_inMath inertial.
Returns
Inertial message.

Specialized conversion from a math inertial to an inertial message.

Parameters
[in]_inMath inertial.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [5/82]

Out gz::sim::convert ( const msgs::Actor _in)

Generic conversion from an actor message to another type.

Specialized conversion from an actor message to an actor SDF object.

Parameters
[in]_inActor message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [6/82]

sdf::Actor gz::sim::convert ( const msgs::Actor _in)

Specialized conversion from an actor message to an actor SDF object.

Parameters
[in]_inActor message.
Returns
Actor SDF object.

Specialized conversion from an actor message to an actor SDF object.

Parameters
[in]_inActor message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [7/82]

Out gz::sim::convert ( const msgs::Atmosphere _in)

Generic conversion from an atmosphere message to another type.

Specialized conversion from an atmosphere message to an atmosphere SDF object.

Parameters
[in]_inAtmosphere message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [8/82]

sdf::Atmosphere gz::sim::convert ( const msgs::Atmosphere _in)

Specialized conversion from an atmosphere message to an atmosphere SDF object.

Parameters
[in]_inAtmosphere message.
Returns
SDF scene.

Specialized conversion from an atmosphere message to an atmosphere SDF object.

Parameters
[in]_inAtmosphere message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [9/82]

Out gz::sim::convert ( const msgs::Axis _in)

Generic conversion from an axis message to another type.

Specialized conversion from an axis message to a joint axis SDF object.

Parameters
[in]_inAxis message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [10/82]

sdf::JointAxis gz::sim::convert ( const msgs::Axis _in)

Specialized conversion from an axis message to a joint axis SDF object.

Parameters
[in]_inAxis message.
Returns
SDF joint axis.

Specialized conversion from an axis message to a joint axis SDF object.

Parameters
[in]_inAxis message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [11/82]

Out gz::sim::convert ( const msgs::AxisAlignedBox _in)

Generic conversion from an axis aligned box message to another type.

Specialized conversion from an math axis aligned box message to an axis aligned box object.

Parameters
[in]_inAxis aligned box message
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [12/82]

math::AxisAlignedBox gz::sim::convert ( const msgs::AxisAlignedBox _in)

Specialized conversion from an math axis aligned box message to an axis aligned box object.

Parameters
[in]_inAxis aligned box object
Returns
Axis aligned box object.

Specialized conversion from an math axis aligned box message to an axis aligned box object.

Parameters
[in]_inAxis aligned box message
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [13/82]

Out gz::sim::convert ( const msgs::Collision _in)

Generic conversion from a collision message to another type.

Specialized conversion from a collision message to a collision SDF object.

Parameters
[in]_inCollision message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [14/82]

sdf::Collision gz::sim::convert ( const msgs::Collision _in)

Specialized conversion from a collision message to a collision SDF object.

Parameters
[in]_inCollision message.
Returns
SDF collision.

Specialized conversion from a collision message to a collision SDF object.

Parameters
[in]_inCollision message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [15/82]

Out gz::sim::convert ( const msgs::Geometry _in)

Generic conversion from a geometry message to another type.

Specialized conversion from a geometry message to a geometry SDF object.

Parameters
[in]_inGeometry message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [16/82]

sdf::Geometry gz::sim::convert ( const msgs::Geometry _in)

Specialized conversion from a geometry message to a geometry SDF object.

Parameters
[in]_inGeometry message.
Returns
SDF geometry.

Specialized conversion from a geometry message to a geometry SDF object.

Parameters
[in]_inGeometry message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [17/82]

Out gz::sim::convert ( const msgs::Inertial _in)

Generic conversion from an inertial message to another type.

Specialized conversion from an inertial message to an inertial math object.

Parameters
[in]_inInertial message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [18/82]

math::Inertiald gz::sim::convert ( const msgs::Inertial _in)

Specialized conversion from an inertial message to an inertial math object.

Parameters
[in]_inInertial message.
Returns
math inertial.

Specialized conversion from an inertial message to an inertial math object.

Parameters
[in]_inInertial message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [19/82]

Out gz::sim::convert ( const msgs::Light _in)

Generic conversion from a light message to another type.

Specialized conversion from a light message to a light SDF object.

Parameters
[in]_inLight message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [20/82]

sdf::Light gz::sim::convert ( const msgs::Light _in)

Specialized conversion from a light message to a light SDF object.

Parameters
[in]_inLight message.
Returns
Light SDF object.

Specialized conversion from a light message to a light SDF object.

Parameters
[in]_inLight message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [21/82]

Out gz::sim::convert ( const msgs::Material _in)

Generic conversion from a material message to another type.

Specialized conversion from a material message to a material SDF object.

Parameters
[in]_inMaterial message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [22/82]

sdf::Material gz::sim::convert ( const msgs::Material _in)

Specialized conversion from a material message to a material SDF object.

Parameters
[in]_inMaterial message.
Returns
SDF material.

Specialized conversion from a material message to a material SDF object.

Parameters
[in]_inMaterial message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [23/82]

Out gz::sim::convert ( const msgs::ParticleEmitter )

Generic conversion from a particle emitter SDF object to another type.

Specialized conversion from a particle emitter SDF object to a particle emitter message object.

Parameters
[in]_inParticle emitter SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [24/82]

sdf::ParticleEmitter gz::sim::convert ( const msgs::ParticleEmitter )

Specialized conversion from a particle emitter SDF object to a particle emitter message object.

Parameters
[in]_inParticle emitter SDF object.
Returns
Particle emitter message.

Specialized conversion from a particle emitter SDF object to a particle emitter message object.

Parameters
[in]_inParticle emitter SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [25/82]

Out gz::sim::convert ( const msgs::Physics _in)

Generic conversion from a physics message to another type.

Specialized conversion from a physics message to a physics SDF object.

Parameters
[in]_inPhysics message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [26/82]

sdf::Physics gz::sim::convert ( const msgs::Physics _in)

Specialized conversion from a physics message to a physics SDF object.

Parameters
[in]_inPhysics message.
Returns
SDF physics.

Specialized conversion from a physics message to a physics SDF object.

Parameters
[in]_inPhysics message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [27/82]

Out gz::sim::convert ( const msgs::Plugin )

Generic conversion from a msgs::Plugin to another type.

Specialized conversion from a msgs::Plugin to an sdf::Plugin.

Parameters
[in]_inmsgs::Plugin.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [28/82]

sdf::Plugin gz::sim::convert ( const msgs::Plugin )

Specialized conversion from a msgs::Plugin to an sdf::Plugin.

Parameters
[in]_inmsgs::Plugin.
Returns
sdf::Plugin.

Specialized conversion from a msgs::Plugin to an sdf::Plugin.

Parameters
[in]_inmsgs::Plugin.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [29/82]

Out gz::sim::convert ( const msgs::Plugin_V )

Generic conversion from a msgs::Plugin_V to another type.

Specialized conversion from a msgs::Plugin_V to an sdf::Plugins.

Parameters
[in]_inmsgs::Plugin_V.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [30/82]

sdf::Plugins gz::sim::convert ( const msgs::Plugin_V )

Specialized conversion from a msgs::Plugin_V to an sdf::Plugins.

Parameters
[in]_inmsgs::Plugin_V.
Returns
sdf::Plugins.

Specialized conversion from a msgs::Plugin_V to an sdf::Plugins.

Parameters
[in]_inmsgs::Plugin_V.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [31/82]

Out gz::sim::convert ( const msgs::Pose _in)

Generic conversion from a msgs Pose to another type.

Specialized conversion for msgs Pose to math Pose.

Parameters
[in]_inmsgs Pose
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [32/82]

math::Pose3d gz::sim::convert ( const msgs::Pose _in)

Specialized conversion for msgs Pose to math Pose.

Parameters
[in]_inmsgs Pose
Returns
math Pose.

Specialized conversion for msgs Pose to math Pose.

Parameters
[in]_inmsgs Pose
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [33/82]

Out gz::sim::convert ( const msgs::Projector )

Generic conversion from a projector SDF object to another type.

Specialized conversion from a projector SDF object to a projector message object.

Parameters
[in]_inProjector SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [34/82]

sdf::Projector gz::sim::convert ( const msgs::Projector )

Specialized conversion from a projector SDF object to a projector message object.

Parameters
[in]_inProjecotr SDF object.
Returns
Projector message.

Specialized conversion from a projector SDF object to a projector message object.

Parameters
[in]_inProjector SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [35/82]

Out gz::sim::convert ( const msgs::Scene _in)

Generic conversion from a scene message to another type.

Specialized conversion from a scene message to a scene SDF object.

Parameters
[in]_inScene message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [36/82]

sdf::Scene gz::sim::convert ( const msgs::Scene _in)

Specialized conversion from a scene message to a scene SDF object.

Parameters
[in]_inScene message.
Returns
SDF scene.

Specialized conversion from a scene message to a scene SDF object.

Parameters
[in]_inScene message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [37/82]

Out gz::sim::convert ( const msgs::Sensor _in)

Generic conversion from a sensor message to another type.

Specialized conversion from a sensor message to a sensor SDF object.

Parameters
[in]_inSensor message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [38/82]

sdf::Sensor gz::sim::convert ( const msgs::Sensor _in)

Specialized conversion from a sensor message to a sensor SDF object.

Parameters
[in]_inSensor message.
Returns
SDF sensor.

Specialized conversion from a sensor message to a sensor SDF object.

Parameters
[in]_inSensor message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [39/82]

Out gz::sim::convert ( const msgs::SensorNoise _in)

Generic conversion from a sensor noise message to another type.

Specialized conversion from a sensor noise message to a noise SDF object.

Parameters
[in]_inSensorNoise message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [40/82]

sdf::Noise gz::sim::convert ( const msgs::SensorNoise _in)

Specialized conversion from a sensor noise message to a noise SDF object.

Parameters
[in]_inSensor noise message.
Returns
SDF noise.

Specialized conversion from a sensor noise message to a noise SDF object.

Parameters
[in]_inSensorNoise message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [41/82]

Out gz::sim::convert ( const msgs::Time _in)

Generic conversion from a time message to another type.

Specialized conversion from a time message to a steady clock duration.

Parameters
[in]_inTime message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [42/82]

std::chrono::steady_clock::duration gz::sim::convert ( const msgs::Time _in)

Specialized conversion from a time message to a steady clock duration.

Parameters
[in]_inTime message.
Returns
Steady clock duration.

Specialized conversion from a time message to a steady clock duration.

Parameters
[in]_inTime message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [43/82]

Out gz::sim::convert ( const msgs::WorldStatistics _in)

Generic conversion from a world statistics message to another type.

Specialized conversion from a world statistics message to an UpdateInfo object.

Parameters
[in]_inWorldStatistics message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [44/82]

UpdateInfo gz::sim::convert ( const msgs::WorldStatistics _in)

Specialized conversion from a world statistics message to an UpdateInfo object.

Parameters
[in]_inWorldStatistics message.
Returns
Update info.

Specialized conversion from a world statistics message to an UpdateInfo object.

Parameters
[in]_inWorldStatistics message.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [45/82]

Out gz::sim::convert ( const sdf::Actor &  _in)

Generic conversion from an SDF actor to another type.

Specialized conversion from an SDF actor to an actor message.

Parameters
[in]_inSDF actor.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [46/82]

msgs::Actor gz::sim::convert ( const sdf::Actor &  _in)

Specialized conversion from an SDF actor to an actor message.

Parameters
[in]_inSDF actor.
Returns
Actor message.

Specialized conversion from an SDF actor to an actor message.

Parameters
[in]_inSDF actor.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [47/82]

Out gz::sim::convert ( const sdf::Atmosphere &  _in)

Generic conversion from an SDF atmosphere to another type.

Specialized conversion from an SDF atmosphere to an atmosphere message.

Parameters
[in]_inSDF atmosphere.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [48/82]

msgs::Atmosphere gz::sim::convert ( const sdf::Atmosphere &  _in)

Specialized conversion from an SDF atmosphere to an atmosphere message.

Parameters
[in]_inSDF atmosphere.
Returns
Atmosphere message.

Specialized conversion from an SDF atmosphere to an atmosphere message.

Parameters
[in]_inSDF atmosphere.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [49/82]

Out gz::sim::convert ( const sdf::Collision &  _in)

Generic conversion from an SDF collision to another type.

Specialized conversion from an SDF collision to a collision message.

Parameters
[in]_inSDF collision.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [50/82]

msgs::Collision gz::sim::convert ( const sdf::Collision &  _in)

Specialized conversion from an SDF collision to a collision message.

Parameters
[in]_inSDF collision.
Returns
Collision message.

Specialized conversion from an SDF collision to a collision message.

Parameters
[in]_inSDF collision.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [51/82]

Out gz::sim::convert ( const sdf::Element &  )

Generic conversion from an SDF element to another type.

Specialized conversion from an SDF element to a plugin message.

Parameters
[in]_inSDF element.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [52/82]

msgs::Plugin gz::sim::convert ( const sdf::Element &  )

Specialized conversion from an SDF element to a plugin message.

Parameters
[in]_inSDF element.
Returns
Plugin message.

Specialized conversion from an SDF element to a plugin message.

Parameters
[in]_inSDF element.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [53/82]

Out gz::sim::convert ( const sdf::Geometry &  _in)

Generic conversion from an SDF geometry to another type.

Specialized conversion from an SDF geometry to a geometry message.

Parameters
[in]_inSDF geometry.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [54/82]

msgs::Geometry gz::sim::convert ( const sdf::Geometry &  _in)

Specialized conversion from an SDF geometry to a geometry message.

Parameters
[in]_inSDF geometry.
Returns
Geometry message.

Specialized conversion from an SDF geometry to a geometry message.

Parameters
[in]_inSDF geometry.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [55/82]

Out gz::sim::convert ( const sdf::Gui &  _in)

Generic conversion from an SDF gui to another type.

Specialized conversion from an SDF gui to a gui message.

Parameters
[in]_inSDF gui.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [56/82]

msgs::GUI gz::sim::convert ( const sdf::Gui &  _in)

Specialized conversion from an SDF gui to a gui message.

Parameters
[in]_inSDF gui.
Returns
Gui message.

Specialized conversion from an SDF gui to a gui message.

Parameters
[in]_inSDF gui.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [57/82]

Out gz::sim::convert ( const sdf::JointAxis &  _in)

Generic conversion from an SDF joint axis to another type.

Specialized conversion from an SDF joint axis to an axis message.

Parameters
[in]_inSDF joint axis.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [58/82]

msgs::Axis gz::sim::convert ( const sdf::JointAxis &  _in)

Specialized conversion from an SDF joint axis to an axis message.

Parameters
[in]_inSDF joint axis.
Returns
Axis message.

Specialized conversion from an SDF joint axis to an axis message.

Parameters
[in]_inSDF joint axis.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [59/82]

Out gz::sim::convert ( const sdf::Light &  _in)

Generic conversion from an SDF light to another type.

Specialized conversion from an SDF light to a light message.

Parameters
[in]_inSDF light.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [60/82]

msgs::Light gz::sim::convert ( const sdf::Light &  _in)

Specialized conversion from an SDF light to a light message.

Parameters
[in]_inSDF light.
Returns
Light message.

Specialized conversion from an SDF light to a light message.

Parameters
[in]_inSDF light.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [61/82]

std::string gz::sim::convert ( const sdf::LightType &  _in)

Generic conversion from a SDF light type to string.

Parameters
[in]_inSDF light type.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [62/82]

Out gz::sim::convert ( const sdf::Material &  _in)

Generic conversion from an SDF material to another type.

Specialized conversion from an SDF material to a material message.

Parameters
[in]_inSDF material.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [63/82]

msgs::Material gz::sim::convert ( const sdf::Material &  _in)

Specialized conversion from an SDF material to a material message.

Parameters
[in]_inSDF material.
Returns
Material message.

Specialized conversion from an SDF material to a material message.

Parameters
[in]_inSDF material.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [64/82]

Out gz::sim::convert ( const sdf::ParticleEmitter &  )

Generic conversion from a particle emitter SDF object to another type.

Specialized conversion from a particle emitter SDF object to a particle emitter message object.

Parameters
[in]_inParticle emitter SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [65/82]

msgs::ParticleEmitter gz::sim::convert ( const sdf::ParticleEmitter &  )

Specialized conversion from a particle emitter SDF object to a particle emitter message object.

Parameters
[in]_inParticle emitter SDF object.
Returns
Particle emitter message.

Specialized conversion from a particle emitter SDF object to a particle emitter message object.

Parameters
[in]_inParticle emitter SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [66/82]

Out gz::sim::convert ( const sdf::Physics &  _in)

Generic conversion from an SDF Physics to another type.

Specialized conversion from an SDF physics to a physics message.

Parameters
[in]_inSDF Physics.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [67/82]

msgs::Physics gz::sim::convert ( const sdf::Physics &  _in)

Specialized conversion from an SDF physics to a physics message.

Parameters
[in]_inSDF physics.
Returns
Physics message.

Specialized conversion from an SDF physics to a physics message.

Parameters
[in]_inSDF Physics.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [68/82]

Out gz::sim::convert ( const sdf::Plugin &  )

Generic conversion from an SDF plugin to another type.

Specialized conversion from an SDF plugin to a plugin message.

Parameters
[in]_inSDF plugin.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [69/82]

msgs::Plugin gz::sim::convert ( const sdf::Plugin &  )

Specialized conversion from an SDF plugin to a plugin message.

Parameters
[in]_inSDF plugin.
Returns
Plugin message.

Specialized conversion from an SDF plugin to a plugin message.

Parameters
[in]_inSDF plugin.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [70/82]

Out gz::sim::convert ( const sdf::Plugins &  )

Generic conversion from an SDF plugins to another type.

Specialized conversion from an SDF plugins to a plugin_v message.

Parameters
[in]_inSDF plugins.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [71/82]

msgs::Plugin_V gz::sim::convert ( const sdf::Plugins &  )

Specialized conversion from an SDF plugins to a plugin_v message.

Parameters
[in]_inSDF plugins.
Returns
Plugin_V message.

Specialized conversion from an SDF plugins to a plugin_v message.

Parameters
[in]_inSDF plugins.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [72/82]

Out gz::sim::convert ( const sdf::Projector &  )

Generic conversion from a projector SDF object to another type.

Specialized conversion from a projector SDF object to a projector message object.

Parameters
[in]_inProjector SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [73/82]

msgs::Projector gz::sim::convert ( const sdf::Projector &  )

Specialized conversion from a projector SDF object to a projector message object.

Parameters
[in]_inProjector SDF object.
Returns
Projector message.

Specialized conversion from a projector SDF object to a projector message object.

Parameters
[in]_inProjector SDF object.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [74/82]

Out gz::sim::convert ( const sdf::Scene &  _in)

Generic conversion from an SDF scene to another type.

Specialized conversion from an SDF scene to a scene message.

Parameters
[in]_inSDF scene.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [75/82]

msgs::Scene gz::sim::convert ( const sdf::Scene &  _in)

Specialized conversion from an SDF scene to a scene message.

Parameters
[in]_inSDF scene.
Returns
Scene message.

Specialized conversion from an SDF scene to a scene message.

Parameters
[in]_inSDF scene.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [76/82]

Out gz::sim::convert ( const sdf::Sensor &  _in)

Generic conversion from an SDF Sensor to another type.

Specialized conversion from an SDF sensor to a sensor message.

Parameters
[in]_inSDF Sensor.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [77/82]

msgs::Sensor gz::sim::convert ( const sdf::Sensor &  _in)

Specialized conversion from an SDF sensor to a sensor message.

Parameters
[in]_inSDF sensor.
Returns
Sensor message.

Specialized conversion from an SDF sensor to a sensor message.

Parameters
[in]_inSDF Sensor.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [78/82]

Out gz::sim::convert ( const std::chrono::steady_clock::duration &  _in)

Generic conversion from a steady clock duration to another type.

Specialized conversion from a steady clock duration to a time message.

Parameters
[in]_inSteady clock duration.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [79/82]

msgs::Time gz::sim::convert ( const std::chrono::steady_clock::duration &  _in)

Specialized conversion from a steady clock duration to a time message.

Parameters
[in]_inSteady clock duration.
Returns
Gazebo time message.

Specialized conversion from a steady clock duration to a time message.

Parameters
[in]_inSteady clock duration.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [80/82]

msgs::Entity_Type convert ( const std::string _in)

Specialized conversion from a string to a sdf light type.

Specialized conversion from a string to an Entity_Type msg.

Generic conversion from a string to another type.

Parameters
[in]_inString with the light type.
Returns
Light type emun SDF object.
Parameters
[in]_instring.
Returns
Conversion result.
Template Parameters
OutOutput type.
Parameters
[in]_instring message.
Returns
Entity_Type.

◆ convert() [81/82]

Out gz::sim::convert ( const UpdateInfo _in)

Generic conversion from update info to another type.

Specialized conversion from update info to a world statistics message.

Parameters
[in]_inUpdate info.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ convert() [82/82]

msgs::WorldStatistics gz::sim::convert ( const UpdateInfo _in)

Specialized conversion from update info to a world statistics message.

Parameters
[in]_inUpdate info.
Returns
World statistics message.

Specialized conversion from update info to a world statistics message.

Parameters
[in]_inUpdate info.
Returns
Conversion result.
Template Parameters
OutOutput type.

◆ enableComponent()

bool gz::sim::enableComponent ( EntityComponentManager _ecm,
Entity  _entity,
bool  _enable = true 
)

Helper function to "enable" a component (i.e. create it if it doesn't exist) or "disable" a component (i.e. remove it if it exists).

Parameters
[in]_ecmMutable reference to the ECM
[in]_entityEntity whose component is being enabled
[in]_enableTrue to enable (create), false to disable (remove). Defaults to true.
Returns
True if a component was created or removed, false if nothing changed.

References EntityComponentManager::Component(), EntityComponentManager::CreateComponent(), exists(), and EntityComponentManager::RemoveComponent().

◆ entitiesFromScopedName()

std::unordered_set<Entity> gz::sim::entitiesFromScopedName ( const std::string _scopedName,
const EntityComponentManager _ecm,
Entity  _relativeTo = kNullEntity,
const std::string _delim = "::" 
)

Helper function to get an entity given its scoped name. The scope may start at any level by default. For example, in this hierarchy:

world_name model_name link_name

All these names will return the link entity:

  • world_name::model_name::link_name
  • model_name::link_name
  • link_name
Parameters
[in]_scopedNameEntity's scoped name.
[in]_ecmImmutable reference to ECM.
[in]_relativeToEntity that the scoped name is relative to. The scoped name does not include the name of this entity. If not provided, the scoped name could be relative to any entity.
[in]_delimDelimiter between names, defaults to "::", it can't be empty.
Returns
All entities that match the scoped name and relative to requirements, or an empty set otherwise.

◆ entityFromMsg()

Entity gz::sim::entityFromMsg ( const EntityComponentManager _ecm,
const msgs::Entity _msg 
)

Helper function to get an entity from an entity message. The returned entity is not guaranteed to exist.

The message is used as follows:

if id not null
  use id
else if name not null and type not null
  use name + type
else
  error
end
Parameters
[in]_ecmEntity component manager
[in]_msgEntity message
Returns
Entity ID, or kNullEntity if a matching entity couldn't be found.

◆ entityTypeId()

ComponentTypeId gz::sim::entityTypeId ( const Entity _entity,
const EntityComponentManager _ecm 
)

Generally, each entity will be of some specific high-level type, such as World, Sensor, Collision, etc, and one type only. The entity type is usually marked by having some component that represents that type, such as components::Visual.

This function returns the type ID of the given entity's type, which can be checked against different types. For example, if the entity is a model, this will be true:

sim::components::Model::typeId == entityTypeId(entity, ecm)

In case the entity isn't of any known type, this will return kComponentTypeIdInvalid.

In case the entity has more than one type, only one of them will be returned. This is not standard usage.

Parameters
[in]_entityEntity to get the type for.
[in]_ecmImmutable reference to ECM.
Returns
ID of entity's type-defining components.

◆ entityTypeStr()

std::string gz::sim::entityTypeStr ( const Entity _entity,
const EntityComponentManager _ecm 
)

Generally, each entity will be of some specific high-level type, such as "world", "sensor", "collision", etc, and one type only.

This function returns a lowercase string for each type. For example, "light", "actor", etc.

In case the entity isn't of any known type, this will return an empty string.

In case the entity has more than one type, only one of them will be returned. This is not standard usage.

Note that this is different from component type names.

Parameters
[in]_entityEntity to get the type for.
[in]_ecmImmutable reference to ECM.
Returns
ID of entity's type-defining components.

◆ getGridFieldCoordinates()

std::optional<math::Vector3d> gz::sim::getGridFieldCoordinates ( const EntityComponentManager _ecm,
const math::Vector3d _worldPosition,
const std::shared_ptr< components::EnvironmentalData > &  _gridField 
)

Get grid field coordinates based on a world position in cartesian coordinate frames.

Parameters
[in]_ecmEntity Component Manager
[in]_worldPositionworld position
[in]_gridFieldGridfield you are interested in.

◆ getGUIConfigPath()

std::string gz::sim::getGUIConfigPath ( )

getGUIConfigPath return the GUI config path

◆ getGUIPluginInstallDir()

std::string gz::sim::getGUIPluginInstallDir ( )

getGUIPluginInstallDir return the GUI plugin install dir

◆ getInstallPrefix()

std::string gz::sim::getInstallPrefix ( )

getInstallPrefix return the install prefix of the library i.e. CMAKE_INSTALL_PREFIX unless the library has been moved

◆ getMediaInstallDir()

std::string gz::sim::getMediaInstallDir ( )

getMediaInstallDir return the media install dir

◆ getPluginInstallDir()

std::string gz::sim::getPluginInstallDir ( )

getPluginInstallDir return the plugin install dir

◆ getPrimitive()

std::string gz::sim::getPrimitive ( const std::string _typeName)

Return an SDF string of one of the available primitive shape or light types.

Parameters
[in]_typeNameType name of the of shape or light to retrieve. Must be one of: box, sphere, cylinder, capsule, ellipsoid, directional, point, or spot.
Returns
String containing SDF description of primitive shape or light. Empty string if the _typeName is invalid.

◆ getPrimitiveLight()

std::string gz::sim::getPrimitiveLight ( const PrimitiveLight _type)

Return an SDF string of one of the available primitive light types.

Parameters
[in]_typeType of light to retrieve
Returns
String containing SDF description of primitive light Empty string if the _type is not supported.

◆ getPrimitiveShape()

std::string gz::sim::getPrimitiveShape ( const PrimitiveShape _type)

Return an SDF string of one of the available primitive shape types.

Parameters
[in]_typeType of shape to retrieve
Returns
String containing SDF description of primitive shape Empty string if the _type is not supported.

◆ getServerConfigPath()

std::string gz::sim::getServerConfigPath ( )

getServerConfigPath return the server config path

◆ getSystemConfigPath()

std::string gz::sim::getSystemConfigPath ( )

getSystemConfigPath return the system config path

◆ getTransformType()

std::optional<TransformType> gz::sim::getTransformType ( const std::string _str)

Given a string return the type of transform.

Parameters
[in]_str- input string
Returns
std::nullopt if string invalid, else corresponding transform

References ADD_VELOCITY_GLOBAL, and ADD_VELOCITY_LOCAL.

◆ getWorldInstallDir()

std::string gz::sim::getWorldInstallDir ( )

getWorldInstallDir return the world install dir

◆ loadMesh()

const common::Mesh* gz::sim::loadMesh ( const sdf::Mesh &  _meshSdf)

Load a mesh from a Mesh SDF DOM.

Parameters
[in]_meshSdfMesh SDF DOM
Returns
The loaded mesh or null if the mesh can not be loaded.

◆ loadPluginInfo()

std::list<ServerConfig::PluginInfo> gz::sim::loadPluginInfo ( bool  _isPlayback = false)

Load plugin information, following ordering.

This method is used when no plugins are found in an SDF file to load either a default or custom set of plugins.

The following order is used to resolve:

  1. Config file located at GZ_SIM_SERVER_CONFIG_PATH environment variable.
    • If GZ_SIM_SERVER_CONFIG_PATH is set but empty, no plugins are loaded.
  2. File at ${GZ_HOMEDIR}/.gz/sim/server.config
  3. File at ${GZ_DATA_INSTALL_DIR}/server.config

If any of the above files exist but are empty, resolution stops and the plugin list will be empty.

Parameters
[in]_isPlaybackIs the server in playback mode. If so, fallback to playback_server.config.
Returns
A list of plugins to load, based on above ordering

◆ parsePluginsFromFile()

std::list<ServerConfig::PluginInfo> gz::sim::parsePluginsFromFile ( const std::string _fname)

Parse plugins from XML configuration file.

Parameters
[in]_fnameAbsolute path to the configuration file to parse.
Returns
A list of all of the plugins found in the configuration file

◆ parsePluginsFromString()

std::list<ServerConfig::PluginInfo> gz::sim::parsePluginsFromString ( const std::string _str)

Parse plugins from XML configuration string.

Parameters
[in]_strXML configuration content to parse
Returns
A list of all of the plugins found in the configuration string.

◆ relativeVel()

math::Vector3d gz::sim::relativeVel ( const Entity _entity,
const EntityComponentManager _ecm 
)

Helper function to compute world velocity of an entity.

Parameters
[in]_entityEntity to get the world pose for
[in]_ecmImmutable reference to ECM.
Returns
World pose of entity

◆ removeParentScope()

std::string gz::sim::removeParentScope ( const std::string _name,
const std::string _delim 
)

Helper function to remove a parent scope from a given name. This removes the first name found before the delimiter.

Parameters
[in]_nameInput name possibly generated by scopedName.
[in]_delimDelimiter between names.
Returns
A new string with the parent scope removed.

◆ resolveSdfWorldFile()

std::string gz::sim::resolveSdfWorldFile ( const std::string _sdfFilename,
const std::string _fuelResourceCache = "" 
)

Convert an SDF world filename string, such as "shapes.sdf", to full system file path. The provided SDF filename may be a Fuel URI, relative path, name of an installed Gazebo world filename, or an absolute path.

Parameters
[in]_sdfFileAn SDF world filename such as:
  1. "shapes.sdf" - This is referencing an installed world file.
  2. "../shapes.sdf" - This is referencing a relative world file.
  3. "/home/user/shapes.sdf" - This is reference an absolute world file.
  4. "https://fuel.ignitionrobotics.org/1.0/openrobotics/worlds/shapes.sdf" This is referencing a Fuel URI. This will download the world file.
[in]_fuelResourceCachePath to a Fuel resource cache, if known.
Returns
Full path to the SDF world file. An empty string is returned if the file could not be found.

◆ resourcePaths()

std::vector<std::string> gz::sim::resourcePaths ( )

Get resource paths based on latest environment variables.

Returns
All paths in the GZ_SIM_RESOURCE_PATH variable.

◆ scopedName()

std::string gz::sim::scopedName ( const Entity _entity,
const EntityComponentManager _ecm,
const std::string _delim = "/",
bool  _includePrefix = true 
)

Helper function to generate scoped name for an entity.

Parameters
[in]_entityEntity to get the name for.
[in]_ecmImmutable reference to ECM.
[in]_delimDelimiter to put between names, defaults to "/".
[in]_includePrefixTrue to include the type prefix before the entity name

◆ set() [1/3]

void gz::sim::set ( msgs::SensorNoise _msg,
const sdf::Noise &  _sdf 
)

Helper function that sets a mutable msgs::SensorNoise object to the values contained in a sdf::Noise object.

Parameters
[out]_msgSensorNoise message to set.
[in]_sdfSDF Noise object.

◆ set() [2/3]

void gz::sim::set ( msgs::Time _msg,
const std::chrono::steady_clock::duration &  _in 
)

Helper function that sets a mutable msgs::Time object to the values contained in a std::chrono::steady_clock::duration object.

Parameters
[out]_msgTime message to set.
[in]_inChrono duration object.

◆ set() [3/3]

void gz::sim::set ( msgs::WorldStatistics _msg,
const UpdateInfo _in 
)

Helper function that sets a mutable msgs::WorldStatistics object to the values contained in a sim::UpdateInfo object.

Parameters
[out]_msgWorldStatistics message to set.
[in]_inUpdateInfo object.

◆ setNoise()

void gz::sim::setNoise ( sdf::Noise &  _noise,
double  _mean,
double  _meanBias,
double  _stdDev,
double  _stdDevBias,
double  _dynamicBiasStdDev,
double  _dynamicBiasCorrelationTime 
)

Helper function that will set all noise properties.

Parameters
[out]_noiseNoise to set
[in]_meanMean value
[in]_meanBiasBias mean value
[in]_stdDevStandard deviation value
[in]_stdDevBiasBias standard deviation value
[in]_dynamicBiasStdDevDynamic bias standard deviation value
[in]_dynamicBiasCorrelationTimeDynamic bias correlation time value

◆ sphericalCoordinates()

std::optional<math::Vector3d> gz::sim::sphericalCoordinates ( Entity  _entity,
const EntityComponentManager _ecm 
)

Get the spherical coordinates for an entity.

Parameters
[in]_entityEntity whose coordinates we want.
[in]_ecmEntity component manager
Returns
The entity's latitude (deg), longitude (deg) and elevation (m). If the entity doesn't have a pose, or the world's spherical coordinates haven't been defined, this will return nullopt.

◆ topicFromScopedName()

std::string gz::sim::topicFromScopedName ( const Entity _entity,
const EntityComponentManager _ecm,
bool  _excludeWorld = true 
)

Helper function that returns a valid Gazebo Transport topic consisting of the scoped name for the provided entity.

For example, if the provided entity has a scoped name of my_model::my_link::my_sensor then the resulting topic name will be /model/my_model/link/my_link/sensor/my_sensor. If _excludeWorld is false, then the topic name will be prefixed by /world/WORLD_NAME/, where WORLD_NAME is the name of the world.

Parameters
[in]_entityThe entity to generate the topic name for.
[in]_ecmThe entity component manager.
[in]_excludeWorldTrue to exclude the world name from the topic.
Returns
A Gazebo Transport topic name based on the scoped name of the provided entity, or empty string if a topic name could not be generated.

◆ topLevelModel()

Entity gz::sim::topLevelModel ( const Entity _entity,
const EntityComponentManager _ecm 
)

Get the top level model of an entity.

Parameters
[in]_entityInput entity
[in]_ecmConstant reference to ECM.
Returns
Entity of top level model. If _entity has no top level model, kNullEntity is returned.

◆ transformFrame()

math::Vector3d gz::sim::transformFrame ( const TransformType  _type,
const math::Pose3d _pose,
const math::Vector3d _velocity,
const math::Vector3d _reading 
)

Given a string return the type of transform.

Parameters
[in]_type- Transform type.
[in]_pose- Global pose of frame to be transformed into.
[in]_velocity- Velocity of current frame.
[in]_reading- vector to be transformed.
Returns
transformed vector.

References ADD_VELOCITY_GLOBAL, ADD_VELOCITY_LOCAL, Quaternion< T >::Inverse(), LOCAL, and Pose3< class >::Rot().

◆ validTopic()

std::string gz::sim::validTopic ( const std::vector< std::string > &  _topics)

Helper function to generate a valid transport topic, given a list of topics ordered by preference. The generated topic will be, in this order:

  1. The first topic unchanged, if valid.
  2. A valid version of the first topic, if possible.
  3. The second topic unchanged, if valid.
  4. A valid version of the second topic, if possible.
  5. ...
  6. If no valid topics could be generated, return an empty string.
Parameters
[in]_topicsTopics ordered by preference.

◆ worldEntity() [1/2]

Entity gz::sim::worldEntity ( const Entity _entity,
const EntityComponentManager _ecm 
)

Get the world to which the given entity belongs.

Parameters
[in]_entityEntity to get the world for.
[in]_ecmImmutable reference to ECM.
Returns
World entity ID.

◆ worldEntity() [2/2]

Entity gz::sim::worldEntity ( const EntityComponentManager _ecm)

Get the first world entity that's found.

Parameters
[in]_ecmImmutable reference to ECM.
Returns
World entity ID.

◆ worldPose()

math::Pose3d gz::sim::worldPose ( const Entity _entity,
const EntityComponentManager _ecm 
)

Helper function to compute world pose of an entity.

Parameters
[in]_entityEntity to get the world pose for
[in]_ecmImmutable reference to ECM.
Returns
World pose of entity

Variable Documentation

◆ EntityComponentManagerPrivate

class GZ_SIM_HIDDEN EntityComponentManagerPrivate

◆ EventManagerPrivate

class GZ_SIM_HIDDEN EventManagerPrivate

◆ kComponentTypeIdInvalid

const ComponentTypeId kComponentTypeIdInvalid = UINT64_MAX
static

Id that indicates an invalid component type.

◆ kNullEntity

◆ kRenderPluginPathEnv

const std::string kRenderPluginPathEnv {"GZ_SIM_RENDER_ENGINE_PATH"}

Environment variable holding paths to custom rendering engine plugins.

◆ kRenderPluginPathEnvDeprecated

const std::string kRenderPluginPathEnvDeprecated
Initial value:
{
"IGN_GAZEBO_RENDER_ENGINE_PATH"}

◆ kResourcePathEnv

const std::string kResourcePathEnv {"GZ_SIM_RESOURCE_PATH"}

Environment variable holding resource paths.

◆ kResourcePathEnvDeprecated

const std::string kResourcePathEnvDeprecated {"IGN_GAZEBO_RESOURCE_PATH"}

◆ kSdfPathEnv

const std::string kSdfPathEnv {"SDF_PATH"}

Environment variable used by SDFormat to find URIs inside <include>

◆ kServerConfigPathEnv

const std::string kServerConfigPathEnv {"GZ_SIM_SERVER_CONFIG_PATH"}

Environment variable holding server config paths.

◆ LinkPrivate

class GZ_SIM_HIDDEN LinkPrivate

◆ ModelPrivate

class GZ_SIM_HIDDEN ModelPrivate

◆ SystemLoaderPrivate

class GZ_SIM_HIDDEN SystemLoaderPrivate

◆ TestFixturePrivate

class GZ_SIM_HIDDEN TestFixturePrivate

◆ WorldPrivate

class GZ_SIM_HIDDEN WorldPrivate