Gazebo Sim

API Reference

9.0.0~pre1
Util.hh File Reference
#include <gz/msgs/entity.pb.h>
#include <memory>
#include <string>
#include <unordered_set>
#include <vector>
#include <gz/common/Mesh.hh>
#include <gz/math/Pose3.hh>
#include <sdf/Mesh.hh>
#include "gz/sim/components/Environment.hh"
#include "gz/sim/config.hh"
#include "gz/sim/Entity.hh"
#include "gz/sim/EntityComponentManager.hh"
#include "gz/sim/Export.hh"
#include "gz/sim/Types.hh"

Go to the source code of this file.

Namespaces

namespace  gz
 This library is part of the Gazebo project.
 
namespace  gz::sim
 Gazebo is a leading open source robotics simulator, that provides high fidelity physics, rendering, and sensor simulation.
 

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.
 
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.
 
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).
 
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:
 
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.
 
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.
 
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.
 
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.
 
const common::MeshloadMesh (const sdf::Mesh &_meshSdf)
 Load a mesh from a Mesh SDF DOM.
 
const common::MeshoptimizeMesh (const sdf::Mesh &_meshSdf, const common::Mesh &_mesh)
 Optimize input mesh.
 
math::Vector3d relativeVel (const Entity &_entity, const EntityComponentManager &_ecm)
 Helper function to compute world velocity of an entity.
 
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.
 
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.
 
std::vector< std::stringresourcePaths ()
 Get resource paths based on latest environment variables.
 
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.
 
std::optional< math::Vector3dsphericalCoordinates (Entity _entity, const EntityComponentManager &_ecm)
 Get the spherical coordinates for an entity.
 
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.
 
Entity topLevelModel (const Entity &_entity, const EntityComponentManager &_ecm)
 Get the top level model of an entity.
 
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:
 
Entity worldEntity (const Entity &_entity, const EntityComponentManager &_ecm)
 Get the world to which the given entity belongs.
 
Entity worldEntity (const EntityComponentManager &_ecm)
 Get the first world entity that's found.
 
math::Pose3d worldPose (const Entity &_entity, const EntityComponentManager &_ecm)
 Helper function to compute world pose of an entity.
 

Variables

const std::string kRenderPluginPathEnv {"GZ_SIM_RENDER_ENGINE_PATH"}
 Environment variable holding paths to custom rendering engine plugins.
 
const std::string kResourcePathEnv {"GZ_SIM_RESOURCE_PATH"}
 Environment variable holding resource paths.
 
const std::string kSdfPathEnv {"SDF_PATH"}
 Environment variable used by SDFormat to find URIs inside <include>
 
const std::string kServerConfigPathEnv {"GZ_SIM_SERVER_CONFIG_PATH"}
 Environment variable holding server config paths.