Files | Namespaces | Classes | Macros | Enumerations | Functions | Variables
Common

Output a message. More...

Files

file  CommonTypes.hh
 

Namespaces

 gazebo::common
 Common namespace.
 

Classes

class  gazebo::common::Animation
 Manages an animation, which is a collection of keyframes and the ability to interpolate between the keyframes. More...
 
class  gazebo::common::AssertionInternalError
 Class for generating Exceptions which come from gazebo assertions. More...
 
class  gazebo::common::AudioDecoder
 An audio decoder based on FFMPEG. More...
 
class  gazebo::common::Battery
 A battery abstraction. More...
 
class  gazebo::common::FileLogger::Buffer
 String buffer for the file logger. More...
 
class  gazebo::common::BVHLoader
 Handles loading BVH animation files. More...
 
class  gazebo::common::ColladaExporter
 Class used to export Collada mesh files. More...
 
class  gazebo::common::ColladaLoader
 Class used to load Collada mesh files. More...
 
class  gazebo::common::Color
 Defines a color. More...
 
class  gazebo::common::Console
 Container for loggers, and global logging options (such as verbose vs. More...
 
class  DEM
 Encapsulates a DEM (Digital Elevation Model) file. More...
 
class  gazebo::common::Dem
 
class  gazebo::common::DemPrivate
 Private data for the Dem class. More...
 
class  gazebo::common::Exception
 Class for generating exceptions. More...
 
class  gazebo::common::FileLogger
 A logger that outputs messages to a file. More...
 
class  gazebo::common::GTSMeshUtils
 Creates GTS utilities for meshes. More...
 
class  gazebo::common::HeightmapData
 Encapsulates a generic heightmap data file. More...
 
class  gazebo::common::Image
 Encapsulates an image. More...
 
class  gazebo::common::ImageHeightmap
 Encapsulates an image that will be interpreted as a heightmap. More...
 
class  gazebo::common::InternalError
 Class for generating Internal Gazebo Errors: those errors which should never happend and represent programming bugs. More...
 
class  gazebo::common::KeyEvent
 Generic description of a keyboard event. More...
 
class  gazebo::common::KeyFrame
 A key frame in an animation. More...
 
class  gazebo::common::Logger
 Terminal logger. More...
 
class  gazebo::common::Material
 Encapsulates description of a material. More...
 
class  gazebo::common::Mesh
 A 3D mesh. More...
 
class  gazebo::common::MeshCSG
 Creates CSG meshes. More...
 
class  gazebo::common::MeshExporter
 Base class for exporting meshes. More...
 
class  gazebo::common::MeshLoader
 Base class for loading meshes. More...
 
class  gazebo::common::MeshManager
 Maintains and manages all meshes. More...
 
class  gazebo::common::ModelDatabase
 Connects to model database, and has utility functions to find models. More...
 
class  gazebo::ModelPlugin
 A plugin with access to physics::Model. More...
 
class  gazebo::common::MouseEvent
 Generic description of a mouse event. More...
 
class  gazebo::common::MovingWindowFilter< T >
 Base class for MovingWindowFilter. More...
 
class  gazebo::common::MovingWindowFilterPrivate< T >
 
class  gazebo::common::NodeAnimation
 Node animation. More...
 
class  gazebo::common::NodeAssignment
 Vertex to node weighted assignement for skeleton animation visualization. More...
 
class  gazebo::common::NodeTransform
 NodeTransform Skeleton.hh common/common.hh More...
 
class  gazebo::common::NumericAnimation
 A numeric animation. More...
 
class  gazebo::common::NumericKeyFrame
 A keyframe for a NumericAnimation. More...
 
class  gazebo::common::PID
 Generic PID controller class. More...
 
class  gazebo::PluginT< T >
 A class which all plugins must inherit from. More...
 
class  gazebo::common::PoseAnimation
 A pose animation. More...
 
class  gazebo::common::PoseKeyFrame
 A keyframe for a PoseAnimation. More...
 
class  gazebo::SensorPlugin
 A plugin with access to physics::Sensor. More...
 
class  SingletonT< T >
 Singleton template class. More...
 
class  gazebo::common::Skeleton
 A skeleton. More...
 
class  gazebo::common::SkeletonAnimation
 Skeleton animation. More...
 
class  gazebo::common::SkeletonNode
 A skeleton node. More...
 
class  gazebo::common::SphericalCoordinates
 Convert spherical coordinates for planetary surfaces. More...
 
class  gazebo::common::SphericalCoordinatesPrivate
 commmon/common.hh More...
 
class  gazebo::common::STLLoader
 Class used to load STL mesh files. More...
 
class  gazebo::common::SubMesh
 A child mesh. More...
 
class  gazebo::common::SystemPaths
 Functions to handle getting system paths, keeps track of: More...
 
class  gazebo::SystemPlugin
 A plugin loaded within the gzserver on startup. More...
 
class  gazebo::common::Time
 A Time class, can be used to hold wall- or sim-time. More...
 
class  gazebo::common::Timer
 A timer class, used to time things in real world walltime. More...
 
class  gazebo::common::Video
 Handle video encoding and decoding using libavcodec. More...
 
class  gazebo::VisualPlugin
 A plugin loaded within the gzserver on startup. More...
 
class  gazebo::WorldPlugin
 A plugin with access to physics::World. More...
 

Macros

#define gzdbg   (gazebo::common::Console::dbg(__FILE__, __LINE__))
 Output a debug message. More...
 
#define gzerr   (gazebo::common::Console::err(__FILE__, __LINE__))
 Output an error message. More...
 
#define gzlog   (gazebo::common::Console::log())
 Output a message to a log file. More...
 
#define gzLogDirectory()   (gazebo::common::Console::log.GetLogDirectory())
 Get the full path of the directory where the log files are stored. More...
 
#define gzLogInit(_prefix, _str)   (gazebo::common::Console::log.Init(_prefix, _str))
 Initialize log file with filename given by _str. More...
 
#define gzmsg   (gazebo::common::Console::msg())
 
#define gzthrow(msg)
 This macro logs an error to the throw stream and throws an exception that contains the file name and line number. More...
 
#define gzwarn   (gazebo::common::Console::warn(__FILE__, __LINE__))
 Output a warning message. More...
 

Enumerations

enum  gazebo::common::Material::BlendMode { gazebo::common::Material::ADD, gazebo::common::Material::MODULATE, gazebo::common::Material::REPLACE, gazebo::common::Material::BLEND_COUNT }
 
enum  gazebo::common::MeshCSG::BooleanOperation { gazebo::common::MeshCSG::UNION, gazebo::common::MeshCSG::INTERSECTION, gazebo::common::MeshCSG::DIFFERENCE }
 An enumeration of the boolean operations. More...
 
enum  gazebo::common::SphericalCoordinates::CoordinateType { gazebo::common::SphericalCoordinates::SPHERICAL = 1, gazebo::common::SphericalCoordinates::ECEF = 2, gazebo::common::SphericalCoordinates::GLOBAL = 3, gazebo::common::SphericalCoordinates::LOCAL = 4 }
 Unique identifiers for coordinate types. More...
 
enum  gazebo::common::KeyEvent::EventType { gazebo::common::KeyEvent::NO_EVENT, gazebo::common::KeyEvent::PRESS, gazebo::common::KeyEvent::RELEASE }
 Key event types enumeration. More...
 
enum  gazebo::common::MouseEvent::EventType {
  gazebo::common::MouseEvent::NO_EVENT, gazebo::common::MouseEvent::MOVE, gazebo::common::MouseEvent::PRESS, gazebo::common::MouseEvent::RELEASE,
  gazebo::common::MouseEvent::SCROLL
}
 Mouse event types enumeration. More...
 
enum  gazebo::common::Time::FormatOption {
  gazebo::common::Time::DAYS = 0, gazebo::common::Time::HOURS = 1, gazebo::common::Time::MINUTES = 2, gazebo::common::Time::SECONDS = 3,
  gazebo::common::Time::MILLISECONDS = 4
}
 
enum  gazebo::common::ColladaExporter::GeometryType { gazebo::common::ColladaExporter::POSITION, gazebo::common::ColladaExporter::NORMAL, gazebo::common::ColladaExporter::UVMAP }
 Geometry types. More...
 
enum  gazebo::common::Logger::LogType { gazebo::common::Logger::STDOUT, gazebo::common::Logger::STDERR }
 
enum  gazebo::common::MouseEvent::MouseButton { gazebo::common::MouseEvent::NO_BUTTON = 0x0, gazebo::common::MouseEvent::LEFT = 0x1, gazebo::common::MouseEvent::MIDDLE = 0x2, gazebo::common::MouseEvent::RIGHT = 0x4 }
 Standard mouse buttons enumeration. More...
 
enum  gazebo::common::Image::PixelFormat {
  gazebo::common::Image::UNKNOWN_PIXEL_FORMAT = 0, gazebo::common::Image::L_INT8, gazebo::common::Image::L_INT16, gazebo::common::Image::RGB_INT8,
  gazebo::common::Image::RGBA_INT8, gazebo::common::Image::BGRA_INT8, gazebo::common::Image::RGB_INT16, gazebo::common::Image::RGB_INT32,
  gazebo::common::Image::BGR_INT8, gazebo::common::Image::BGR_INT16, gazebo::common::Image::BGR_INT32, gazebo::common::Image::R_FLOAT16,
  gazebo::common::Image::RGB_FLOAT16, gazebo::common::Image::R_FLOAT32, gazebo::common::Image::RGB_FLOAT32, gazebo::common::Image::BAYER_RGGB8,
  gazebo::common::Image::BAYER_RGGR8, gazebo::common::Image::BAYER_GBRG8, gazebo::common::Image::BAYER_GRBG8, gazebo::common::Image::PIXEL_FORMAT_COUNT
}
 Pixel formats enumeration. More...
 
enum  gazebo::PluginType {
  gazebo::WORLD_PLUGIN, gazebo::MODEL_PLUGIN, gazebo::SENSOR_PLUGIN, gazebo::SYSTEM_PLUGIN,
  gazebo::VISUAL_PLUGIN, gazebo::GUI_PLUGIN
}
 Used to specify the type of plugin. More...
 
enum  gazebo::common::SubMesh::PrimitiveType {
  gazebo::common::SubMesh::POINTS, gazebo::common::SubMesh::LINES, gazebo::common::SubMesh::LINESTRIPS, gazebo::common::SubMesh::TRIANGLES,
  gazebo::common::SubMesh::TRIFANS, gazebo::common::SubMesh::TRISTRIPS
}
 An enumeration of the geometric mesh primitives. More...
 
enum  gazebo::common::Material::ShadeMode {
  gazebo::common::Material::FLAT, gazebo::common::Material::GOURAUD, gazebo::common::Material::PHONG, gazebo::common::Material::BLINN,
  gazebo::common::Material::SHADE_COUNT
}
 
enum  gazebo::common::SkeletonNode::SkeletonNodeType { gazebo::common::SkeletonNode::NODE, gazebo::common::SkeletonNode::JOINT }
 enumeration of node types More...
 
enum  gazebo::common::SphericalCoordinates::SurfaceType { gazebo::common::SphericalCoordinates::EARTH_WGS84 = 1 }
 Unique identifiers for planetary surface models. More...
 
enum  gazebo::common::NodeTransform::TransformType { gazebo::common::NodeTransform::TRANSLATE, gazebo::common::NodeTransform::ROTATE, gazebo::common::NodeTransform::SCALE, gazebo::common::NodeTransform::MATRIX }
 Enumeration of the transform types. More...
 

Functions

 gazebo::common::MovingWindowFilter< T >::MovingWindowFilter ()
 Constructor. More...
 
 gazebo::common::MovingWindowFilterPrivate< T >::MovingWindowFilterPrivate ()
 
virtual gazebo::common::MovingWindowFilter< T >::~MovingWindowFilter ()
 Destructor. More...
 
GZ_COMMON_VISIBLE void gazebo::common::add_search_path_suffix (const std::string &_suffix)
 add path sufix to common::SystemPaths More...
 
static bool gazebo::common::GTSMeshUtils::DelaunayTriangulation (const std::vector< ignition::math::Vector2d > &_vertices, const std::vector< ignition::math::Vector2i > &_edges, SubMesh *_submesh)
 Perform delaunay triangulation on input vertices. More...
 
void gazebo::common::ModelDatabase::DownloadDependencies (const std::string &_path)
 Download all dependencies for a give model path. More...
 
GZ_COMMON_VISIBLE std::string gazebo::common::find_file (const std::string &_file)
 search for file in common::SystemPaths More...
 
GZ_COMMON_VISIBLE std::string gazebo::common::find_file (const std::string &_file, bool _searchLocalPath)
 search for file in common::SystemPaths More...
 
GZ_COMMON_VISIBLE std::string gazebo::common::find_file_path (const std::string &_file)
 search for a file in common::SystemPaths More...
 
void gazebo::common::ModelDatabase::Fini ()
 Finalize the model database. More...
 
gazebo::common::MovingWindowFilter< T >::Get ()
 Get filtered result. More...
 
template<typename T >
std::string gazebo::common::get_sha1 (const T &_buffer)
 Compute the SHA1 hash of an array of bytes. More...
 
std::string gazebo::common::ModelDatabase::GetDBConfig (const std::string &_uri)
 Return the database.config file as a string. More...
 
GZ_COMMON_VISIBLE const char * gazebo::common::getEnv (const char *_name)
 Cross platform retrieval of an environment variable. More...
 
std::string gazebo::common::ModelDatabase::GetModelConfig (const std::string &_uri)
 Return the model.config file as a string. More...
 
std::string gazebo::common::ModelDatabase::GetModelFile (const std::string &_uri)
 Get a model's SDF file based on a URI. More...
 
std::string gazebo::common::ModelDatabase::GetModelName (const std::string &_uri)
 Get the name of a model based on a URI. More...
 
std::string gazebo::common::ModelDatabase::GetModelPath (const std::string &_uri, bool _forceDownload=false)
 Get the local path to a model. More...
 
std::map< std::string,
std::string > 
gazebo::common::ModelDatabase::GetModels ()
 Returns the dictionary of all the model names. More...
 
event::ConnectionPtr gazebo::common::ModelDatabase::GetModels (boost::function< void(const std::map< std::string, std::string > &)> _func)
 Get the dictionary of all model names via a callback. More...
 
std::string gazebo::common::ModelDatabase::GetURI ()
 Returns the the global model database URI. More...
 
bool gazebo::common::MovingWindowFilter< T >::GetWindowFilled () const
 Get whether the window has been filled. More...
 
unsigned int gazebo::common::MovingWindowFilter< T >::GetWindowSize () const
 Get the window size. More...
 
bool gazebo::common::ModelDatabase::HasModel (const std::string &_modelName)
 Returns true if the model exists on the database. More...
 
GZ_COMMON_VISIBLE void gazebo::common::load ()
 Load the common library. More...
 
void gazebo::common::MovingWindowFilter< T >::SetWindowSize (unsigned int _n)
 Set window size. More...
 
void gazebo::common::ModelDatabase::Start (bool _fetchImmediately=false)
 Start the model database. More...
 
void gazebo::common::MovingWindowFilter< T >::Update (T _val)
 Update value of filter. More...
 

Variables

static std::string gazebo::common::PixelFormatNames []
 String names for the pixel formats. More...
 

Detailed Description

Output a message.

Macro Definition Documentation

#define gzdbg   (gazebo::common::Console::dbg(__FILE__, __LINE__))

Output a debug message.

#define gzerr   (gazebo::common::Console::err(__FILE__, __LINE__))
#define gzlog   (gazebo::common::Console::log())

Output a message to a log file.

#define gzLogDirectory ( )    (gazebo::common::Console::log.GetLogDirectory())

Get the full path of the directory where the log files are stored.

Returns
Full path of the directory
#define gzLogInit (   _prefix,
  _str 
)    (gazebo::common::Console::log.Init(_prefix, _str))

Initialize log file with filename given by _str.

If called twice, it will close currently in use and open a new log file.

Parameters
[in]_prefixPrefix added to the directory where the log file will be created.
[in]_strName of log file for gzlog messages.
#define gzmsg   (gazebo::common::Console::msg())
#define gzthrow (   msg)
Value:
{std::ostringstream throwStream;\
throwStream << msg << std::endl << std::flush;\
throw gazebo::common::Exception(__FILE__, __LINE__, throwStream.str()); }
Class for generating exceptions.
Definition: Exception.hh:45

This macro logs an error to the throw stream and throws an exception that contains the file name and line number.

Referenced by gazebo::transport::TopicManager::Advertise(), gazebo::transport::CallbackHelperT< M >::GetMsgType(), and gazebo::transport::SubscribeOptions::Init().

#define gzwarn   (gazebo::common::Console::warn(__FILE__, __LINE__))

Enumeration Type Documentation

Enumerator
ADD 
MODULATE 
REPLACE 
BLEND_COUNT 

An enumeration of the boolean operations.

Enumerator
UNION 
INTERSECTION 
DIFFERENCE 

Unique identifiers for coordinate types.

Enumerator
SPHERICAL 

Latitude, Longitude and Altitude by SurfaceType.

ECEF 

Earth centered, earth fixed Cartesian.

GLOBAL 

Local tangent plane (East, North, Up)

LOCAL 

Heading-adjusted tangent plane (X, Y, Z)

Key event types enumeration.

Enumerator
NO_EVENT 
PRESS 
RELEASE 

Mouse event types enumeration.

Enumerator
NO_EVENT 

No event.

MOVE 

Move event.

PRESS 

Press event.

RELEASE 

Release event.

SCROLL 

Scroll event.

Enumerator
DAYS 

Days.

HOURS 

Hours.

MINUTES 

Minutes.

SECONDS 

Seconds.

MILLISECONDS 

Milliseconds.

Geometry types.

Enumerator
POSITION 
NORMAL 
UVMAP 

Output destination type.

Enumerator
STDOUT 

Output to stdout.

STDERR 

Output to stderr.

Standard mouse buttons enumeration.

Enumerator
NO_BUTTON 

No button.

LEFT 

Left button.

MIDDLE 

Middle button.

RIGHT 

Right button.

Pixel formats enumeration.

Enumerator
UNKNOWN_PIXEL_FORMAT 
L_INT8 
L_INT16 
RGB_INT8 
RGBA_INT8 
BGRA_INT8 
RGB_INT16 
RGB_INT32 
BGR_INT8 
BGR_INT16 
BGR_INT32 
R_FLOAT16 
RGB_FLOAT16 
R_FLOAT32 
RGB_FLOAT32 
BAYER_RGGB8 
BAYER_RGGR8 
BAYER_GBRG8 
BAYER_GRBG8 
PIXEL_FORMAT_COUNT 

Used to specify the type of plugin.

Enumerator
WORLD_PLUGIN 

A World plugin.

MODEL_PLUGIN 

A Model plugin.

SENSOR_PLUGIN 

A Sensor plugin.

SYSTEM_PLUGIN 

A System plugin.

VISUAL_PLUGIN 

A Visual plugin.

GUI_PLUGIN 

A GUI plugin.

An enumeration of the geometric mesh primitives.

Enumerator
POINTS 
LINES 
LINESTRIPS 
TRIANGLES 
TRIFANS 
TRISTRIPS 
Enumerator
FLAT 
GOURAUD 
PHONG 
BLINN 
SHADE_COUNT 

enumeration of node types

Enumerator
NODE 
JOINT 

Unique identifiers for planetary surface models.

Enumerator
EARTH_WGS84 

Model of reference ellipsoid for earth, based on WGS 84 standard.

see wikipedia: World_Geodetic_System

Enumeration of the transform types.

Enumerator
TRANSLATE 
ROTATE 
SCALE 
MATRIX 

Function Documentation

template<typename T >
gazebo::common::MovingWindowFilter< T >::MovingWindowFilter ( )

Constructor.

template<typename T >
gazebo::common::MovingWindowFilterPrivate< T >::MovingWindowFilterPrivate ( )

FIXME hardcoded initial value for now

template<typename T >
gazebo::common::MovingWindowFilter< T >::~MovingWindowFilter ( )
virtual

Destructor.

References NULL.

GZ_COMMON_VISIBLE void gazebo::common::add_search_path_suffix ( const std::string &  _suffix)

add path sufix to common::SystemPaths

Parameters
[in]_suffixThe suffix to add.
static bool gazebo::common::GTSMeshUtils::DelaunayTriangulation ( const std::vector< ignition::math::Vector2d > &  _vertices,
const std::vector< ignition::math::Vector2i > &  _edges,
SubMesh _submesh 
)
static

Perform delaunay triangulation on input vertices.

Parameters
[in]_verticesA list of all vertices
[in]_edgesA list of edges. Each edge is made of 2 vertex indices from _vertices
[out]_submeshA submesh that will be populated with the resulting triangles.
Returns
True on success.
void gazebo::common::ModelDatabase::DownloadDependencies ( const std::string &  _path)

Download all dependencies for a give model path.

Look's in the model's manifest file (_path/model.config) for all models listed in the <depend> block, and downloads the models if necessary.

Parameters
[in]_pathPath to a model.
GZ_COMMON_VISIBLE std::string gazebo::common::find_file ( const std::string &  _file)

search for file in common::SystemPaths

Parameters
[in]_fileName of the file to find.
Returns
The path containing the file.
GZ_COMMON_VISIBLE std::string gazebo::common::find_file ( const std::string &  _file,
bool  _searchLocalPath 
)

search for file in common::SystemPaths

Parameters
[in]_fileName of the file to find.
[in]_searchLocalPathTrue to search in the current working directory.
Returns
The path containing the file.
GZ_COMMON_VISIBLE std::string gazebo::common::find_file_path ( const std::string &  _file)

search for a file in common::SystemPaths

Parameters
[in]_filethe file name to look for.
Returns
The path containing the file.
void gazebo::common::ModelDatabase::Fini ( )

Finalize the model database.

template<typename T >
T gazebo::common::MovingWindowFilter< T >::Get ( )

Get filtered result.

Returns
latest filtered value
template<typename T >
std::string gazebo::common::get_sha1 ( const T &  _buffer)

Compute the SHA1 hash of an array of bytes.

Parameters
[in]_bufferInput sequence. The permitted data types for this function are std::string and any STL container.
Returns
The string representation (40 character) of the SHA1 hash.

References NULL.

std::string gazebo::common::ModelDatabase::GetDBConfig ( const std::string &  _uri)

Return the database.config file as a string.

Returns
The database config file from the model database.
GZ_COMMON_VISIBLE const char* gazebo::common::getEnv ( const char *  _name)

Cross platform retrieval of an environment variable.

Parameters
[in]_nameName of the environment variable to get.
Returns
Environment variable contents, or NULL on error.
std::string gazebo::common::ModelDatabase::GetModelConfig ( const std::string &  _uri)

Return the model.config file as a string.

Returns
The model config file from the model database.
std::string gazebo::common::ModelDatabase::GetModelFile ( const std::string &  _uri)

Get a model's SDF file based on a URI.

Get a model file based on a URI. If the model is on a remote server, then the model fetched and installed locally.

Parameters
[in]_uriThe URI of the model
Returns
The full path and filename to the SDF file
std::string gazebo::common::ModelDatabase::GetModelName ( const std::string &  _uri)

Get the name of a model based on a URI.

The URI must be fully qualified: http://gazebosim.org/gazebo_models/ground_plane or model://gazebo_models

Parameters
[in]_urithe model uri
Returns
the model's name.
std::string gazebo::common::ModelDatabase::GetModelPath ( const std::string &  _uri,
bool  _forceDownload = false 
)

Get the local path to a model.

Get the path to a model based on a URI. If the model is on a remote server, then the model fetched and installed locally.

Parameters
[in]_urithe model uri
[in]_forceDownloadTrue to skip searching local paths.
Returns
path to a model directory
std::map<std::string, std::string> gazebo::common::ModelDatabase::GetModels ( )

Returns the dictionary of all the model names.

This is a blocking call. Which means it will wait for the ModelDatabase to download the model list.

Returns
a map of model names, indexed by their full URI.
event::ConnectionPtr gazebo::common::ModelDatabase::GetModels ( boost::function< void(const std::map< std::string, std::string > &)>  _func)

Get the dictionary of all model names via a callback.

This is the non-blocking version of ModelDatabase::GetModels

Parameters
[in]_funcCallback function that receives the list of models.
Returns
A boost shared pointer. This pointer must remain valid in order to receive the callback.
std::string gazebo::common::ModelDatabase::GetURI ( )

Returns the the global model database URI.

Returns
the URI.
template<typename T >
bool gazebo::common::MovingWindowFilter< T >::GetWindowFilled ( ) const

Get whether the window has been filled.

Returns
True if the window has been filled.
template<typename T >
unsigned int gazebo::common::MovingWindowFilter< T >::GetWindowSize ( ) const

Get the window size.

Returns
The size of the moving window.
bool gazebo::common::ModelDatabase::HasModel ( const std::string &  _modelName)

Returns true if the model exists on the database.

Parameters
[in]_modelNameURI of the model (eg: model://my_model_name).
Returns
True if the model was found.
GZ_COMMON_VISIBLE void gazebo::common::load ( )

Load the common library.

template<typename T >
void gazebo::common::MovingWindowFilter< T >::SetWindowSize ( unsigned int  _n)

Set window size.

Parameters
[in]_nnew desired window size
void gazebo::common::ModelDatabase::Start ( bool  _fetchImmediately = false)

Start the model database.

Parameters
[in]_fetchImmediatelyTrue to fetch the models without waiting.
template<typename T >
void gazebo::common::MovingWindowFilter< T >::Update ( _val)

Update value of filter.

Parameters
[in]_valnew raw value

Variable Documentation

std::string gazebo::common::PixelFormatNames[]
static
Initial value:
=
{
"UNKNOWN_PIXEL_FORMAT",
"L_INT8",
"L_INT16",
"RGB_INT8",
"RGBA_INT8",
"BGRA_INT8",
"RGB_INT16",
"RGB_INT32",
"BGR_INT8",
"BGR_INT16",
"BGR_INT32",
"R_FLOAT16",
"RGB_FLOAT16",
"R_FLOAT32",
"RGB_FLOAT32",
"BAYER_RGGB8",
"BAYER_RGGR8",
"BAYER_GBRG8",
"BAYER_GRBG8"
}

String names for the pixel formats.

See also
Image::PixelFormat.