Messages

All messages and helper functions. More...

Namespaces

 gazebo::msgs
 Messages namespace.
 

Classes

class  GazeboGenerator
 Google protobuf message generator for gazebo::msgs. More...
 
class  MsgFactory
 A factory that generates protobuf message based on a string type. More...
 

Macros

#define GZ_REGISTER_STATIC_MSG(_msgtype, _classname)
 Static message registration macro. More...
 

Functions

GAZEBO_VISIBLE void AddBoxLink (msgs::Model &_model, const double _mass, const ignition::math::Vector3d &_size)
 Add a simple box link to a Model message. More...
 
GAZEBO_VISIBLE void AddCylinderLink (msgs::Model &_model, const double _mass, const double _radius, const double _length)
 Add a simple cylinder link to a Model message. More...
 
GAZEBO_VISIBLE void AddLinkGeom (Model &_msg, const Geometry &_geom)
 Add a link with a collision and visual of specified geometry to a model message. More...
 
GAZEBO_VISIBLE void AddSphereLink (msgs::Model &_model, const double _mass, const double _radius)
 Add a simple sphere link to a Model message. More...
 
GAZEBO_VISIBLE msgs::Axis AxisFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Axis from an axis SDF element. More...
 
GAZEBO_VISIBLE msgs::CameraSensor CameraSensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::CameraSensor from a camera sensor SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr CameraSensorToSDF (const msgs::CameraSensor &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::CameraSensor. More...
 
GAZEBO_VISIBLE msgs::Collision CollisionFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Collision from a collision SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr CollisionToSDF (const msgs::Collision &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Collision. More...
 
GAZEBO_VISIBLE msgs::ContactSensor ContactSensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::ContactSensor from a contact sensor SDF element. More...
 
GAZEBO_VISIBLE msgs::Vector3d Convert (const ignition::math::Vector3d &_v)
 Convert a ignition::math::Vector3 to a msgs::Vector3d. More...
 
GAZEBO_VISIBLE msgs::Vector2d Convert (const ignition::math::Vector2d &_v)
 Convert a ignition::math::Vector2d to a msgs::Vector2d. More...
 
GAZEBO_VISIBLE msgs::Quaternion Convert (const ignition::math::Quaterniond &_q)
 Convert a ignition::math::Quaterniond to a msgs::Quaternion. More...
 
GAZEBO_VISIBLE msgs::Pose Convert (const ignition::math::Pose3d &_p)
 Convert a ignition::math::Pose to a msgs::Pose. More...
 
GAZEBO_VISIBLE msgs::Color Convert (const ignition::math::Color &_c)
 Convert an ignition::math::Color to a msgs::Color. More...
 
GAZEBO_VISIBLE msgs::Time Convert (const common::Time &_t)
 Convert a common::Time to a msgs::Time. More...
 
GAZEBO_VISIBLE msgs::Inertial Convert (const ignition::math::Inertiald &_i)
 Convert an ignition::math::Inertiald to a msgs::Inertial. More...
 
GAZEBO_VISIBLE msgs::Inertial Convert (const ignition::math::MassMatrix3d &_m)
 Convert an ignition::math::MassMatrix3d to a msgs::Inertial. More...
 
GAZEBO_VISIBLE msgs::PlaneGeom Convert (const ignition::math::Planed &_p)
 Convert a ignition::math::Planed to a msgs::PlaneGeom. More...
 
GAZEBO_VISIBLE ignition::math::Inertiald Convert (const msgs::Inertial &_i)
 Convert a msgs::Inertial to an ignition::math::Inertiald. More...
 
GAZEBO_VISIBLE ignition::math::Color Convert (const msgs::Color &_c)
 Convert a msgs::Color to a ignition::math::Color. More...
 
GAZEBO_VISIBLE common::Time Convert (const msgs::Time &_t)
 Convert a msgs::Time to a common::Time. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const double _v)
 Convert a double to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const int _i)
 Convert an int to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const std::string &_s)
 Convert a std::string to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const char *_s)
 Convert a string literal to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const bool _b)
 Convert a bool to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const ignition::math::Vector3d &_v)
 Convert an ignition::math::Vector3d to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const ignition::math::Color &_c)
 Convert an ignition::math::Color to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const ignition::math::Pose3d &_p)
 Convert an ignition::math::Pose3d to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const ignition::math::Quaterniond &_q)
 Convert an ignition::math::Quaterniond to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Any ConvertAny (const common::Time &_t)
 Convert a common::Time to a msgs::Any. More...
 
GAZEBO_VISIBLE msgs::Geometry::Type ConvertGeometryType (const std::string &_str)
 Convert a string to a msgs::Geometry::Type enum. More...
 
GAZEBO_VISIBLE std::string ConvertGeometryType (const msgs::Geometry::Type _type)
 Convert a msgs::Geometry::Type to a string. More...
 
GAZEBO_VISIBLE ignition::math::Vector3d ConvertIgn (const msgs::Vector3d &_v)
 Convert a msgs::Vector3d to an ignition::math::Vector. More...
 
GAZEBO_VISIBLE ignition::math::Vector2d ConvertIgn (const msgs::Vector2d &_v)
 Convert a msgs::Vector2d to an ignition::math::Vector2d. More...
 
GAZEBO_VISIBLE ignition::math::Quaterniond ConvertIgn (const msgs::Quaternion &_q)
 Convert a msgs::Quaternion to an ignition::math::Quaternion. More...
 
GAZEBO_VISIBLE ignition::math::Pose3d ConvertIgn (const msgs::Pose &_p)
 Convert a msgs::Pose to an ignition::math::Pose. More...
 
GAZEBO_VISIBLE ignition::math::Planed ConvertIgn (const msgs::PlaneGeom &_p)
 Convert a msgs::PlaneGeom to an ignition::math::Planed. More...
 
GAZEBO_VISIBLE ignition::msgs::Color ConvertIgnMsg (const msgs::Color &_msg)
 Convert gazebo::msgs::Color to ignition::msgs::Color. More...
 
GAZEBO_VISIBLE msgs::Color ConvertIgnMsg (const ignition::msgs::Color &_msg)
 Convert ignition::msgs::Color to gazebo::msgs::Color. More...
 
GAZEBO_VISIBLE ignition::msgs::Material::ShaderType ConvertIgnMsg (const msgs::Material::ShaderType &_type)
 Convert gazebo::msgs::Material::ShaderType to ignition::msgs::Material::ShaderType. More...
 
GAZEBO_VISIBLE msgs::Material::ShaderType ConvertIgnMsg (const ignition::msgs::Material::ShaderType &_type)
 Convert ignition::msgs::Material::ShaderType to gazebo::msgs::Material::ShaderType. More...
 
GAZEBO_VISIBLE ignition::msgs::Material::Script ConvertIgnMsg (const msgs::Material::Script &_script)
 Convert gazebo::msgs::Material::Script to ignition::msgs::Material::Script. More...
 
GAZEBO_VISIBLE msgs::Material::Script ConvertIgnMsg (const ignition::msgs::Material::Script &_script)
 Convert ignition::msgs::Material::Script to gazebo::msgs::Material::Script. More...
 
GAZEBO_VISIBLE ignition::msgs::Material ConvertIgnMsg (const msgs::Material &_msg)
 Convert gazebo::msgs::Material to ignition::msgs::Material. More...
 
GAZEBO_VISIBLE msgs::Material ConvertIgnMsg (const ignition::msgs::Material &_msg)
 Convert ignition::msgs::Material to gazebo::msgs::Material. More...
 
GAZEBO_VISIBLE msgs::Joint::Type ConvertJointType (const std::string &_str)
 Convert a string to a msgs::Joint::Type enum. More...
 
GAZEBO_VISIBLE std::string ConvertJointType (const msgs::Joint::Type &_type)
 Convert a msgs::Joint::Type to a string. More...
 
GAZEBO_VISIBLE msgs::Material::ShaderType ConvertShaderType (const std::string &_str)
 Convert a string to a msgs::Material::ShaderType enum. More...
 
GAZEBO_VISIBLE std::string ConvertShaderType (const msgs::Material::ShaderType &_type)
 Convert a msgs::ShaderType to a string. More...
 
GAZEBO_VISIBLE msgs::Request * CreateRequest (const std::string &_request, const std::string &_data="")
 Create a request message. More...
 
GAZEBO_VISIBLE msgs::Fog FogFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Fog from a fog SDF element. More...
 
GAZEBO_VISIBLE msgs::Friction FrictionFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Friction from a friction SDF element. More...
 
GAZEBO_VISIBLE msgs::Geometry GeometryFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Geometry from a geometry SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr GeometryToSDF (const msgs::Geometry &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Geometry If _sdf is supplied and the _msg has non-empty repeated elements, any existing sdf elements will be removed from _sdf prior to adding the new elements from _msg. More...
 
GAZEBO_VISIBLE msgs::Header * GetHeader (google::protobuf::Message &_message)
 Get the header from a protobuf message. More...
 
GAZEBO_VISIBLE msgs::GPSSensor GPSSensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::GPSSensor from a gps sensor SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr GPSSensorToSDF (const msgs::GPSSensor &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::GPSSensor. More...
 
GAZEBO_VISIBLE msgs::GUI GUIFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::GUI from a GUI SDF element. More...
 
GAZEBO_VISIBLE msgs::IMUSensor IMUSensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::IMUSensor from an imu sensor SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr IMUSensorToSDF (const msgs::IMUSensor &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::IMUSensor. More...
 
GAZEBO_VISIBLE sdf::ElementPtr InertialToSDF (const msgs::Inertial &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Inertial. More...
 
GAZEBO_VISIBLE void Init (google::protobuf::Message &_message, const std::string &_id="")
 Initialize a message. More...
 
GAZEBO_VISIBLE msgs::Joint JointFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Joint from a joint SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr JointToSDF (const msgs::Joint &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from msgs::Joint. More...
 
GAZEBO_VISIBLE msgs::Light LightFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Light from a light SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr LightToSDF (const msgs::Light &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Light. More...
 
GAZEBO_VISIBLE sdf::ElementPtr LinkToSDF (const msgs::Link &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Link. More...
 
GAZEBO_VISIBLE msgs::LogicalCameraSensor LogicalCameraSensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::LogicalCameraSensor from a logical camera sensor. More...
 
GAZEBO_VISIBLE sdf::ElementPtr LogicalCameraSensorToSDF (const msgs::LogicalCameraSensor &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::LogicalCameraSensor. More...
 
GAZEBO_VISIBLE sdf::ElementPtr MaterialToSDF (const msgs::Material &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Material If _sdf is supplied and _msg has script uri's the <uri> elements will be removed from _sdf. More...
 
GAZEBO_VISIBLE msgs::MeshGeom MeshFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::MeshGeom from a mesh SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr MeshToSDF (const msgs::MeshGeom &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Mesh. More...
 
GAZEBO_VISIBLE sdf::ElementPtr ModelToSDF (const msgs::Model &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from msgs::Model. More...
 
GAZEBO_VISIBLE msgs::Plugin PluginFromSDF (const sdf::ElementPtr _sdf)
 Create a msgs::Plugin from a plugin SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr PluginToSDF (const msgs::Plugin &_plugin, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Plugin. More...
 
GAZEBO_VISIBLE msgs::RaySensor RaySensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::RaySensor from a ray sensor SDF element. More...
 
GAZEBO_VISIBLE msgs::Scene SceneFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Scene from a scene SDF element. More...
 
GAZEBO_VISIBLE msgs::Sensor SensorFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Sensor from a sensor SDF element. More...
 
GAZEBO_VISIBLE msgs::SensorNoise SensorNoiseFromSDF (sdf::ElementPtr _elem)
 Create a msgs::SensorNoise from a sensor noise SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr SensorNoiseToSDF (const msgs::SensorNoise &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::SensorNoise. More...
 
GAZEBO_VISIBLE void Set (common::Image &_img, const msgs::Image &_msg)
 Convert a msgs::Image to a common::Image. More...
 
GAZEBO_VISIBLE void Set (msgs::Image *_msg, const common::Image &_i)
 Set a msgs::Image from a common::Image. More...
 
GAZEBO_VISIBLE void Set (msgs::Vector3d *_pt, const ignition::math::Vector3d &_v)
 Set a msgs::Vector3d from an ignition::math::Vector3d. More...
 
GAZEBO_VISIBLE void Set (msgs::Vector2d *_pt, const ignition::math::Vector2d &_v)
 Set a msgs::Vector2d from an ignition::math::Vector2d. More...
 
GAZEBO_VISIBLE void Set (msgs::Quaternion *_q, const ignition::math::Quaterniond &_v)
 Set a msgs::Quaternion from an ignition::math::Quaterniond. More...
 
GAZEBO_VISIBLE void Set (msgs::Pose *_p, const ignition::math::Pose3d &_v)
 Set a msgs::Pose from an ignition::math::Pose3d. More...
 
GAZEBO_VISIBLE void Set (msgs::Color *_c, const ignition::math::Color &_v)
 Set a msgs::Color from an ignition::math::Color. More...
 
GAZEBO_VISIBLE void Set (msgs::Time *_t, const common::Time &_v)
 Set a msgs::Time from a common::Time. More...
 
GAZEBO_VISIBLE void Set (msgs::SphericalCoordinates *_s, const common::SphericalCoordinates &_v)
 Set a msgs::SphericalCoordinates from a common::SphericalCoordinates object. More...
 
GAZEBO_VISIBLE void Set (msgs::Inertial *_i, const ignition::math::Inertiald &_m)
 Set a msgs::Inertial from an ignition::math::Inertiald. More...
 
GAZEBO_VISIBLE void Set (msgs::Inertial *_i, const ignition::math::MassMatrix3d &_m)
 Set a msgs::Inertial from an ignition::math::MassMatrix3d. More...
 
GAZEBO_VISIBLE void Set (msgs::PlaneGeom *_p, const ignition::math::Planed &_v)
 Set a msgs::Plane from an ignition::math::Planed. More...
 
GAZEBO_VISIBLE void Stamp (msgs::Header *_header)
 Time stamp a header. More...
 
GAZEBO_VISIBLE void Stamp (msgs::Time *_time)
 Set the time in a time message. More...
 
GAZEBO_VISIBLE msgs::Surface SurfaceFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Surface from a surface SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr SurfaceToSDF (const msgs::Surface &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Surface. More...
 
GAZEBO_VISIBLE msgs::TrackVisual TrackVisualFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::TrackVisual from a track visual SDF element. More...
 
GAZEBO_VISIBLE msgs::Visual VisualFromSDF (sdf::ElementPtr _sdf)
 Create a msgs::Visual from a visual SDF element. More...
 
GAZEBO_VISIBLE sdf::ElementPtr VisualToSDF (const msgs::Visual &_msg, sdf::ElementPtr _sdf=sdf::ElementPtr())
 Create or update an SDF element from a msgs::Visual. More...
 

Detailed Description

All messages and helper functions.

Macro Definition Documentation

◆ GZ_REGISTER_STATIC_MSG

#define GZ_REGISTER_STATIC_MSG (   _msgtype,
  _classname 
)
Value:
GAZEBO_VISIBLE \
boost::shared_ptr<google::protobuf::Message> New##_classname() \
{ \
return boost::shared_ptr<gazebo::msgs::_classname>(\
new gazebo::msgs::_classname); \
} \
class GAZEBO_VISIBLE Msg##_classname \
{ \
public: Msg##_classname() \
{ \
gazebo::msgs::MsgFactory::RegisterMsg(_msgtype, New##_classname);\
} \
}; \
static Msg##_classname GzMsgInitializer;
static void RegisterMsg(const std::string &_msgType, MsgFactoryFn _factoryfn)
Register a message.
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:59

Static message registration macro.

Use this macro to register messages.

Parameters
[in]_msgtypeMessage type name.
[in]_classnameClass name for message.

Function Documentation

◆ AddBoxLink()

GAZEBO_VISIBLE void gazebo::msgs::AddBoxLink ( msgs::Model &  _model,
const double  _mass,
const ignition::math::Vector3d &  _size 
)

Add a simple box link to a Model message.

The size and mass of the box are specified, and a single collision is added, along with an inertial block corresponding to a box of uniform density.

Parameters
[out]_modelThe msgs::Model to which the link is added.
[in]_massMass of the box.
[in]_sizeSize of the box.

◆ AddCylinderLink()

GAZEBO_VISIBLE void gazebo::msgs::AddCylinderLink ( msgs::Model &  _model,
const double  _mass,
const double  _radius,
const double  _length 
)

Add a simple cylinder link to a Model message.

The radius, length, and mass of the cylinder are specified, and a single collision is added, along with an inertial block corresponding to a cylinder of uniform density with an axis of symmetry along the Z axis.

Parameters
[out]_modelThe msgs::Model to which the link is added.
[in]_massMass of the cylinder.
[in]_radiusRadius of the cylinder.
[in]_lengthLength of the cylinder.

◆ AddLinkGeom()

GAZEBO_VISIBLE void gazebo::msgs::AddLinkGeom ( Model &  _msg,
const Geometry &  _geom 
)

Add a link with a collision and visual of specified geometry to a model message.

It does not set any inertial values.

Parameters
[out]_modelThe msgs::Model object to receive a new link.
[in]_geomGeometry to be added to collision and visual.

◆ AddSphereLink()

GAZEBO_VISIBLE void gazebo::msgs::AddSphereLink ( msgs::Model &  _model,
const double  _mass,
const double  _radius 
)

Add a simple sphere link to a Model message.

The size and mass of the sphere are specified, and a single collision is added, along with an inertial block corresponding to a sphere of uniform density.

Parameters
[out]_modelThe msgs::Model to which the link is added.
[in]_massMass of the sphere.
[in]_radiusRadius of the sphere.

◆ AxisFromSDF()

GAZEBO_VISIBLE msgs::Axis gazebo::msgs::AxisFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Axis from an axis SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Axis object

◆ CameraSensorFromSDF()

GAZEBO_VISIBLE msgs::CameraSensor gazebo::msgs::CameraSensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::CameraSensor from a camera sensor SDF element.

Parameters
[in]_sdfThe camera sensor sdf element
Returns
The new msgs::CameraSensor object
See also
SensorFromSDF

◆ CameraSensorToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::CameraSensorToSDF ( const msgs::CameraSensor &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::CameraSensor.

Parameters
[in]_msgCameraSensor messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ CollisionFromSDF()

GAZEBO_VISIBLE msgs::Collision gazebo::msgs::CollisionFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Collision from a collision SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Collision object Note: This function does not support frame semantics. The pose of the output message will be just the value of the <pose> tag.

◆ CollisionToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::CollisionToSDF ( const msgs::Collision &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Collision.

Parameters
[in]_msgCollision messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ ContactSensorFromSDF()

GAZEBO_VISIBLE msgs::ContactSensor gazebo::msgs::ContactSensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::ContactSensor from a contact sensor SDF element.

Parameters
[in]_sdfThe contact sensor sdf element
Returns
The new msgs::ContactSensor object
See also
SensorFromSDF

◆ Convert() [1/12]

GAZEBO_VISIBLE msgs::Vector3d gazebo::msgs::Convert ( const ignition::math::Vector3d &  _v)

Convert a ignition::math::Vector3 to a msgs::Vector3d.

Parameters
[in]_vThe vector to convert
Returns
A msgs::Vector3d object

◆ Convert() [2/12]

GAZEBO_VISIBLE msgs::Vector2d gazebo::msgs::Convert ( const ignition::math::Vector2d &  _v)

Convert a ignition::math::Vector2d to a msgs::Vector2d.

Parameters
[in]_vThe vector to convert
Returns
A msgs::Vector2d object

◆ Convert() [3/12]

GAZEBO_VISIBLE msgs::Quaternion gazebo::msgs::Convert ( const ignition::math::Quaterniond &  _q)

Convert a ignition::math::Quaterniond to a msgs::Quaternion.

Parameters
[in]_qThe quaternion to convert
Returns
A msgs::Quaternion object

◆ Convert() [4/12]

GAZEBO_VISIBLE msgs::Pose gazebo::msgs::Convert ( const ignition::math::Pose3d &  _p)

Convert a ignition::math::Pose to a msgs::Pose.

Parameters
[in]_pThe pose to convert
Returns
A msgs::Pose object

◆ Convert() [5/12]

GAZEBO_VISIBLE msgs::Color gazebo::msgs::Convert ( const ignition::math::Color &  _c)

Convert an ignition::math::Color to a msgs::Color.

Parameters
[in]_cThe color to convert
Returns
A msgs::Color object

◆ Convert() [6/12]

GAZEBO_VISIBLE msgs::Time gazebo::msgs::Convert ( const common::Time _t)

Convert a common::Time to a msgs::Time.

Parameters
[in]_tThe time to convert
Returns
A msgs::Time object

◆ Convert() [7/12]

GAZEBO_VISIBLE msgs::Inertial gazebo::msgs::Convert ( const ignition::math::Inertiald &  _i)

Convert an ignition::math::Inertiald to a msgs::Inertial.

Parameters
[in]_iThe Inertiald to convert
Returns
A msgs::Inertial object

◆ Convert() [8/12]

GAZEBO_VISIBLE msgs::Inertial gazebo::msgs::Convert ( const ignition::math::MassMatrix3d &  _m)

Convert an ignition::math::MassMatrix3d to a msgs::Inertial.

Parameters
[in]_mThe MassMatrix3d to convert
Returns
A msgs::Inertial object

◆ Convert() [9/12]

GAZEBO_VISIBLE msgs::PlaneGeom gazebo::msgs::Convert ( const ignition::math::Planed &  _p)

Convert a ignition::math::Planed to a msgs::PlaneGeom.

Parameters
[in]_pThe plane to convert
Returns
A msgs::PlaneGeom object

◆ Convert() [10/12]

GAZEBO_VISIBLE ignition::math::Inertiald gazebo::msgs::Convert ( const msgs::Inertial &  _i)

Convert a msgs::Inertial to an ignition::math::Inertiald.

Parameters
[in]_iThe inertial to convert
Returns
An ignition::math::Inertiald object

◆ Convert() [11/12]

GAZEBO_VISIBLE ignition::math::Color gazebo::msgs::Convert ( const msgs::Color &  _c)

Convert a msgs::Color to a ignition::math::Color.

Parameters
[in]_cThe color to convert
Returns
An ignition::math::Color object

◆ Convert() [12/12]

GAZEBO_VISIBLE common::Time gazebo::msgs::Convert ( const msgs::Time &  _t)

Convert a msgs::Time to a common::Time.

Parameters
[in]_tThe time to convert
Returns
A common::Time object

◆ ConvertAny() [1/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const double  _v)

Convert a double to a msgs::Any.

Parameters
[in]_vThe double to convert.
Returns
A msgs::Any object.

Referenced by IntrospectionManager::Register().

◆ ConvertAny() [2/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const int  _i)

Convert an int to a msgs::Any.

Parameters
[in]_iThe int to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [3/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const std::string &  _s)

Convert a std::string to a msgs::Any.

Parameters
[in]_sThe string to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [4/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const char *  _s)

Convert a string literal to a msgs::Any.

Parameters
[in]_sThe string to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [5/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const bool  _b)

Convert a bool to a msgs::Any.

Parameters
[in]_bThe bool to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [6/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const ignition::math::Vector3d &  _v)

Convert an ignition::math::Vector3d to a msgs::Any.

Parameters
[in]_vThe vector to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [7/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const ignition::math::Color &  _c)

Convert an ignition::math::Color to a msgs::Any.

Parameters
[in]_cThe color to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [8/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const ignition::math::Pose3d &  _p)

Convert an ignition::math::Pose3d to a msgs::Any.

Parameters
[in]_pThe pose to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [9/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const ignition::math::Quaterniond &  _q)

Convert an ignition::math::Quaterniond to a msgs::Any.

Parameters
[in]_qThe quaternion to convert.
Returns
A msgs::Any object.

◆ ConvertAny() [10/10]

GAZEBO_VISIBLE msgs::Any gazebo::msgs::ConvertAny ( const common::Time _t)

Convert a common::Time to a msgs::Any.

Parameters
[in]_tThe time to convert.
Returns
A msgs::Any object.

◆ ConvertGeometryType() [1/2]

GAZEBO_VISIBLE msgs::Geometry::Type gazebo::msgs::ConvertGeometryType ( const std::string &  _str)

Convert a string to a msgs::Geometry::Type enum.

Parameters
[in]_strGeometry type string.
Returns
A msgs::Geometry::Type enum.

◆ ConvertGeometryType() [2/2]

GAZEBO_VISIBLE std::string gazebo::msgs::ConvertGeometryType ( const msgs::Geometry::Type  _type)

Convert a msgs::Geometry::Type to a string.

Parameters
[in]_typeA msgs::Geometry::Type enum.
Returns
Geometry type string.

◆ ConvertIgn() [1/5]

GAZEBO_VISIBLE ignition::math::Vector3d gazebo::msgs::ConvertIgn ( const msgs::Vector3d &  _v)

Convert a msgs::Vector3d to an ignition::math::Vector.

Parameters
[in]_vThe plane to convert
Returns
An ignition::math::Vector3 object

◆ ConvertIgn() [2/5]

GAZEBO_VISIBLE ignition::math::Vector2d gazebo::msgs::ConvertIgn ( const msgs::Vector2d &  _v)

Convert a msgs::Vector2d to an ignition::math::Vector2d.

Parameters
[in]_vThe vector2 to convert
Returns
An ignition::math::Vector2d object

◆ ConvertIgn() [3/5]

GAZEBO_VISIBLE ignition::math::Quaterniond gazebo::msgs::ConvertIgn ( const msgs::Quaternion &  _q)

Convert a msgs::Quaternion to an ignition::math::Quaternion.

Parameters
[in]_qThe quaternion to convert
Returns
An ignition::math::Quaterniond object

◆ ConvertIgn() [4/5]

GAZEBO_VISIBLE ignition::math::Pose3d gazebo::msgs::ConvertIgn ( const msgs::Pose &  _p)

Convert a msgs::Pose to an ignition::math::Pose.

Parameters
[in]_pThe pose to convert
Returns
An ignition::math::Pose object

◆ ConvertIgn() [5/5]

GAZEBO_VISIBLE ignition::math::Planed gazebo::msgs::ConvertIgn ( const msgs::PlaneGeom &  _p)

Convert a msgs::PlaneGeom to an ignition::math::Planed.

Parameters
[in]_pThe plane to convert
Returns
An ignition::math::Planed object

◆ ConvertIgnMsg() [1/8]

GAZEBO_VISIBLE ignition::msgs::Color gazebo::msgs::ConvertIgnMsg ( const msgs::Color &  _msg)

Convert gazebo::msgs::Color to ignition::msgs::Color.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [2/8]

GAZEBO_VISIBLE msgs::Color gazebo::msgs::ConvertIgnMsg ( const ignition::msgs::Color &  _msg)

Convert ignition::msgs::Color to gazebo::msgs::Color.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [3/8]

GAZEBO_VISIBLE ignition::msgs::Material::ShaderType gazebo::msgs::ConvertIgnMsg ( const msgs::Material::ShaderType &  _type)

Convert gazebo::msgs::Material::ShaderType to ignition::msgs::Material::ShaderType.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [4/8]

GAZEBO_VISIBLE msgs::Material::ShaderType gazebo::msgs::ConvertIgnMsg ( const ignition::msgs::Material::ShaderType &  _type)

Convert ignition::msgs::Material::ShaderType to gazebo::msgs::Material::ShaderType.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [5/8]

GAZEBO_VISIBLE ignition::msgs::Material::Script gazebo::msgs::ConvertIgnMsg ( const msgs::Material::Script &  _script)

Convert gazebo::msgs::Material::Script to ignition::msgs::Material::Script.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [6/8]

GAZEBO_VISIBLE msgs::Material::Script gazebo::msgs::ConvertIgnMsg ( const ignition::msgs::Material::Script &  _script)

Convert ignition::msgs::Material::Script to gazebo::msgs::Material::Script.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [7/8]

GAZEBO_VISIBLE ignition::msgs::Material gazebo::msgs::ConvertIgnMsg ( const msgs::Material &  _msg)

Convert gazebo::msgs::Material to ignition::msgs::Material.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertIgnMsg() [8/8]

GAZEBO_VISIBLE msgs::Material gazebo::msgs::ConvertIgnMsg ( const ignition::msgs::Material &  _msg)

Convert ignition::msgs::Material to gazebo::msgs::Material.

Parameters
[in]_msgThe message to convert
Returns
The resulting message

◆ ConvertJointType() [1/2]

GAZEBO_VISIBLE msgs::Joint::Type gazebo::msgs::ConvertJointType ( const std::string &  _str)

Convert a string to a msgs::Joint::Type enum.

Parameters
[in]_strJoint type string.
Returns
A msgs::Joint::Type enum. Defaults to REVOLUTE if _str is unrecognized.

◆ ConvertJointType() [2/2]

GAZEBO_VISIBLE std::string gazebo::msgs::ConvertJointType ( const msgs::Joint::Type &  _type)

Convert a msgs::Joint::Type to a string.

Parameters
[in]_typeA msgs::Joint::Type enum.
Returns
Joint type string. Returns "unknown" if _type is unrecognized.

◆ ConvertShaderType() [1/2]

GAZEBO_VISIBLE msgs::Material::ShaderType gazebo::msgs::ConvertShaderType ( const std::string &  _str)

Convert a string to a msgs::Material::ShaderType enum.

Parameters
[in]_strShader type string.
Returns
A msgs::Material::ShaderType enum. Defaults to VERTEX if _str is unrecognized.

◆ ConvertShaderType() [2/2]

GAZEBO_VISIBLE std::string gazebo::msgs::ConvertShaderType ( const msgs::Material::ShaderType &  _type)

Convert a msgs::ShaderType to a string.

Parameters
[in]_typeA msgs::ShaderType enum.
Returns
Shader type string. Returns "unknown" if _type is unrecognized.

◆ CreateRequest()

GAZEBO_VISIBLE msgs::Request* gazebo::msgs::CreateRequest ( const std::string &  _request,
const std::string &  _data = "" 
)

Create a request message.

Parameters
[in]_requestRequest string
[in]_dataOptional data string
Returns
A Request message

◆ FogFromSDF()

GAZEBO_VISIBLE msgs::Fog gazebo::msgs::FogFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Fog from a fog SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Fog object

◆ FrictionFromSDF()

GAZEBO_VISIBLE msgs::Friction gazebo::msgs::FrictionFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Friction from a friction SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Friction object

◆ GeometryFromSDF()

GAZEBO_VISIBLE msgs::Geometry gazebo::msgs::GeometryFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Geometry from a geometry SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Geometry object

◆ GeometryToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::GeometryToSDF ( const msgs::Geometry &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Geometry If _sdf is supplied and the _msg has non-empty repeated elements, any existing sdf elements will be removed from _sdf prior to adding the new elements from _msg.

Parameters
[in]_msgGeometry messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ GetHeader()

GAZEBO_VISIBLE msgs::Header* gazebo::msgs::GetHeader ( google::protobuf::Message &  _message)

Get the header from a protobuf message.

Parameters
[in]_messageA google protobuf message
Returns
A pointer to the message's header

◆ GPSSensorFromSDF()

GAZEBO_VISIBLE msgs::GPSSensor gazebo::msgs::GPSSensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::GPSSensor from a gps sensor SDF element.

Parameters
[in]_sdfThe GPS sensor sdf element
Returns
The new msgs::GPSSensor object
See also
SensorFromSDF

◆ GPSSensorToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::GPSSensorToSDF ( const msgs::GPSSensor &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::GPSSensor.

Parameters
[in]_msgGPSSensor messsage
[in]_sdfIf supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ GUIFromSDF()

GAZEBO_VISIBLE msgs::GUI gazebo::msgs::GUIFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::GUI from a GUI SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::GUI object

◆ IMUSensorFromSDF()

GAZEBO_VISIBLE msgs::IMUSensor gazebo::msgs::IMUSensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::IMUSensor from an imu sensor SDF element.

Parameters
[in]_sdfThe IMU sensor sdf element
Returns
The new msgs::IMUSensor object
See also
SensorFromSDF

◆ IMUSensorToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::IMUSensorToSDF ( const msgs::IMUSensor &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::IMUSensor.

Parameters
[in]_msgIMUSensor messsage
[in]_sdfIf supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ InertialToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::InertialToSDF ( const msgs::Inertial &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Inertial.

Parameters
[in]_msgInertial messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ Init()

GAZEBO_VISIBLE void gazebo::msgs::Init ( google::protobuf::Message &  _message,
const std::string &  _id = "" 
)

◆ JointFromSDF()

GAZEBO_VISIBLE msgs::Joint gazebo::msgs::JointFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Joint from a joint SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Joint object

◆ JointToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::JointToSDF ( const msgs::Joint &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from msgs::Joint.

Parameters
[in]_msgThe msgs::Joint object.
[in]_sdfif supplied, performs an update from _sdf instead of creating a new sdf element.
Returns
The new SDF element.

◆ LightFromSDF()

GAZEBO_VISIBLE msgs::Light gazebo::msgs::LightFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Light from a light SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Light object

◆ LightToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::LightToSDF ( const msgs::Light &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Light.

Parameters
[in]_msgLight messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ LinkToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::LinkToSDF ( const msgs::Link &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Link.

If _sdf is supplied and _msg has any collisions or visuals, the <collision> and <visual> elements will be removed from _sdf.

Parameters
[in]_msgLink messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ LogicalCameraSensorFromSDF()

GAZEBO_VISIBLE msgs::LogicalCameraSensor gazebo::msgs::LogicalCameraSensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::LogicalCameraSensor from a logical camera sensor.

SDF element

Parameters
[in]_sdfThe logical camera sensor sdf element
Returns
The new msgs::LogicalCameraSensor object
See also
SensorFromSDF

◆ LogicalCameraSensorToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::LogicalCameraSensorToSDF ( const msgs::LogicalCameraSensor &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::LogicalCameraSensor.

Parameters
[in]_msgLogicalCameraSensor messsage
[in]_sdfIf supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ MaterialToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::MaterialToSDF ( const msgs::Material &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Material If _sdf is supplied and _msg has script uri's the <uri> elements will be removed from _sdf.

Parameters
[in]_msgMaterial messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ MeshFromSDF()

GAZEBO_VISIBLE msgs::MeshGeom gazebo::msgs::MeshFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::MeshGeom from a mesh SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::MeshGeom object

◆ MeshToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::MeshToSDF ( const msgs::MeshGeom &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Mesh.

Parameters
[in]_msgMesh messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ ModelToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::ModelToSDF ( const msgs::Model &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from msgs::Model.

If _sdf is supplied and _msg has any links or joints, the <link> and <joint> elements will be removed from _sdf.

Parameters
[in]_msgThe msgs::Model object.
[in]_sdfif supplied, performs an update from _sdf instead of creating a new sdf element.
Returns
The new SDF element.

◆ PluginFromSDF()

GAZEBO_VISIBLE msgs::Plugin gazebo::msgs::PluginFromSDF ( const sdf::ElementPtr  _sdf)

Create a msgs::Plugin from a plugin SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Plugin object

◆ PluginToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::PluginToSDF ( const msgs::Plugin &  _plugin,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Plugin.

Parameters
[in]_msgPlugin messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ RaySensorFromSDF()

GAZEBO_VISIBLE msgs::RaySensor gazebo::msgs::RaySensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::RaySensor from a ray sensor SDF element.

Parameters
[in]_sdfThe ray sensor sdf element
Returns
The new msgs::RaySensor object
See also
SensorFromSDF

◆ SceneFromSDF()

GAZEBO_VISIBLE msgs::Scene gazebo::msgs::SceneFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Scene from a scene SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Scene object

◆ SensorFromSDF()

GAZEBO_VISIBLE msgs::Sensor gazebo::msgs::SensorFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Sensor from a sensor SDF element.

Parameters
[in]_sdfThe sensor sdf element
Returns
The new msgs::Sensor object
See also
CameraSensorFromSDF
RaySensorFromSDF
ContactSensorFromSDF
LogicalCameraSensorFromSDF
GPSSensorFromSDF
ImuSensorFromSDF

◆ SensorNoiseFromSDF()

GAZEBO_VISIBLE msgs::SensorNoise gazebo::msgs::SensorNoiseFromSDF ( sdf::ElementPtr  _elem)

Create a msgs::SensorNoise from a sensor noise SDF element.

Parameters
[in]_sdfThe sensor noise sdf element
Returns
The new msgs::SensorNoise object
See also
SensorFromSDF

◆ SensorNoiseToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::SensorNoiseToSDF ( const msgs::SensorNoise &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::SensorNoise.

Parameters
[in]_msgSensorNoise messsage
[in]_sdfIf supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ Set() [1/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( common::Image _img,
const msgs::Image &  _msg 
)

Convert a msgs::Image to a common::Image.

Parameters
[out]_imgThe common::Image container
[in]_msgThe Image message to convert

◆ Set() [2/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Image *  _msg,
const common::Image _i 
)

Set a msgs::Image from a common::Image.

Parameters
[out]_msgA msgs::Image pointer
[in]_iA common::Image reference

◆ Set() [3/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Vector3d *  _pt,
const ignition::math::Vector3d &  _v 
)

Set a msgs::Vector3d from an ignition::math::Vector3d.

Parameters
[out]_ptA msgs::Vector3d pointer
[in]_vAn ignition::math::Vector3d reference

◆ Set() [4/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Vector2d *  _pt,
const ignition::math::Vector2d &  _v 
)

Set a msgs::Vector2d from an ignition::math::Vector2d.

Parameters
[out]_ptA msgs::Vector2d pointer
[in]_vAn ignition::math::Vector2d reference

◆ Set() [5/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Quaternion *  _q,
const ignition::math::Quaterniond &  _v 
)

Set a msgs::Quaternion from an ignition::math::Quaterniond.

Parameters
[out]_qA msgs::Quaternion pointer
[in]_vAn ignition::math::Quaterniond reference

◆ Set() [6/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Pose *  _p,
const ignition::math::Pose3d &  _v 
)

Set a msgs::Pose from an ignition::math::Pose3d.

Parameters
[out]_pA msgs::Pose pointer
[in]_vAn ignition::math::Pose3d reference

◆ Set() [7/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Color *  _c,
const ignition::math::Color &  _v 
)

Set a msgs::Color from an ignition::math::Color.

Parameters
[out]_pA msgs::Color pointer
[in]_vAn ignition::math::Color reference

◆ Set() [8/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Time *  _t,
const common::Time _v 
)

Set a msgs::Time from a common::Time.

Parameters
[out]_pA msgs::Time pointer
[in]_vA common::Time reference

◆ Set() [9/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::SphericalCoordinates *  _s,
const common::SphericalCoordinates _v 
)

Set a msgs::SphericalCoordinates from a common::SphericalCoordinates object.

Parameters
[out]_pA msgs::SphericalCoordinates pointer.
[in]_vA common::SphericalCoordinates reference

◆ Set() [10/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Inertial *  _i,
const ignition::math::Inertiald &  _m 
)

Set a msgs::Inertial from an ignition::math::Inertiald.

Parameters
[out]_iA msgs::Inertial pointer
[in]_mAn ignition::math::Inertiald reference

◆ Set() [11/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::Inertial *  _i,
const ignition::math::MassMatrix3d &  _m 
)

Set a msgs::Inertial from an ignition::math::MassMatrix3d.

Parameters
[out]_iA msgs::Inertial pointer
[in]_mAn ignition::math::MassMatrix3d reference

◆ Set() [12/12]

GAZEBO_VISIBLE void gazebo::msgs::Set ( msgs::PlaneGeom *  _p,
const ignition::math::Planed &  _v 
)

Set a msgs::Plane from an ignition::math::Planed.

Parameters
[out]_pA msgs::Plane pointer
[in]_vAn ignition::math::Planed reference

◆ Stamp() [1/2]

GAZEBO_VISIBLE void gazebo::msgs::Stamp ( msgs::Header *  _header)

Time stamp a header.

Parameters
[in]_headerHeader to stamp

◆ Stamp() [2/2]

GAZEBO_VISIBLE void gazebo::msgs::Stamp ( msgs::Time *  _time)

Set the time in a time message.

Parameters
[in]_timeA Time message

◆ SurfaceFromSDF()

GAZEBO_VISIBLE msgs::Surface gazebo::msgs::SurfaceFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Surface from a surface SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Surface object

◆ SurfaceToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::SurfaceToSDF ( const msgs::Surface &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Surface.

Parameters
[in]_msgSurface messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.

◆ TrackVisualFromSDF()

GAZEBO_VISIBLE msgs::TrackVisual gazebo::msgs::TrackVisualFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::TrackVisual from a track visual SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::TrackVisual object

◆ VisualFromSDF()

GAZEBO_VISIBLE msgs::Visual gazebo::msgs::VisualFromSDF ( sdf::ElementPtr  _sdf)

Create a msgs::Visual from a visual SDF element.

Parameters
[in]_sdfThe sdf element
Returns
The new msgs::Visual object Note: This function does not support frame semantics. The pose of the output message will be just the value of the <pose> tag.

◆ VisualToSDF()

GAZEBO_VISIBLE sdf::ElementPtr gazebo::msgs::VisualToSDF ( const msgs::Visual &  _msg,
sdf::ElementPtr  _sdf = sdf::ElementPtr() 
)

Create or update an SDF element from a msgs::Visual.

Parameters
[in]_msgVisual messsage
[in]_sdfif supplied, performs an update from _msg instead of creating a new sdf element.
Returns
The new SDF element.