| 
| 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::Quaternion 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 common::Color &_c) | 
|   | Convert a common::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::PlaneGeom  | Convert (const ignition::math::Planed &_p) | 
|   | Convert a ignition::math::Planed to a msgs::PlaneGeom.  More...
  | 
|   | 
| GAZEBO_VISIBLE common::Color  | Convert (const msgs::Color &_c) | 
|   | Convert a msgs::Color to a common::Color.  More...
  | 
|   | 
| GAZEBO_VISIBLE common::Time  | Convert (const msgs::Time &_t) | 
|   | Convert a msgs::Time to a common::Time.  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 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::GUI  | GUIFromSDF (sdf::ElementPtr _sdf) | 
|   | Create a msgs::GUI from a GUI SDF element.  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 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 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 common::Color &_v) | 
|   | Set a msgs::Color from a common::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::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...
  | 
|   |