All messages and helper functions. More...
Namespaces | |
| namespace | gazebo::msgs | 
| Messages namespace.  | |
Classes | |
| class | google::protobuf::compiler::cpp::GazeboGenerator | 
| Google protobuf message generator for gazebo::msgs.  More... | |
Functions | |
| msgs::Vector3d | gazebo::msgs::Convert (const math::Vector3 &_v) | 
| Convert a math::Vector3 to a msgs::Vector3d.   | |
| msgs::Quaternion | gazebo::msgs::Convert (const math::Quaternion &_q) | 
| Convert a math::Quaternion to a msgs::Quaternion.   | |
| msgs::Pose | gazebo::msgs::Convert (const math::Pose &_p) | 
| Convert a math::Pose to a msgs::Pose.   | |
| msgs::Color | gazebo::msgs::Convert (const common::Color &_c) | 
| Convert a common::Color to a msgs::Color.   | |
| msgs::Time | gazebo::msgs::Convert (const common::Time &_t) | 
| Convert a common::Time to a msgs::Time.   | |
| msgs::PlaneGeom | gazebo::msgs::Convert (const math::Plane &_p) | 
| Convert a math::Plane to a msgs::PlaneGeom.   | |
| math::Vector3 | gazebo::msgs::Convert (const msgs::Vector3d &_v) | 
| Convert a msgs::Vector3d to a math::Vector.   | |
| math::Quaternion | gazebo::msgs::Convert (const msgs::Quaternion &_q) | 
| Convert a msgs::Quaternion to a math::Quaternion.   | |
| math::Pose | gazebo::msgs::Convert (const msgs::Pose &_p) | 
| Convert a msgs::Pose to a math::Pose.   | |
| common::Color | gazebo::msgs::Convert (const msgs::Color &_c) | 
| Convert a msgs::Color to a common::Color.   | |
| common::Time | gazebo::msgs::Convert (const msgs::Time &_t) | 
| Convert a msgs::Time to a common::Time.   | |
| math::Plane | gazebo::msgs::Convert (const msgs::PlaneGeom &_p) | 
| Convert a msgs::PlaneGeom to a common::Plane.   | |
| msgs::Request * | gazebo::msgs::CreateRequest (const std::string &_request, const std::string &_data="") | 
| Create a request message.   | |
| msgs::Fog | gazebo::msgs::FogFromSDF (sdf::ElementPtr _sdf) | 
| Create a msgs::Fog from a fog SDF element.   | |
| msgs::Header * | gazebo::msgs::GetHeader (google::protobuf::Message &_message) | 
| Get the header from a protobuf message.   | |
| msgs::GUI | gazebo::msgs::GUIFromSDF (sdf::ElementPtr _sdf) | 
| Create a msgs::GUI from a GUI SDF element.   | |
| void | gazebo::msgs::Init (google::protobuf::Message &_message, const std::string &_id="") | 
| Initialize a message.   | |
| msgs::Light | gazebo::msgs::LightFromSDF (sdf::ElementPtr _sdf) | 
| Create a msgs::Light from a light SDF element.   | |
| msgs::Scene | gazebo::msgs::SceneFromSDF (sdf::ElementPtr _sdf) | 
| Create a msgs::Scene from a scene SDF element.   | |
| void | gazebo::msgs::Set (common::Image &_img, const msgs::Image &_msg) | 
| Convert a msgs::Image to a common::Image.   | |
| void | gazebo::msgs::Set (msgs::Image *_msg, const common::Image &_i) | 
| Set a msgs::Image from a common::Image.   | |
| void | gazebo::msgs::Set (msgs::Vector3d *_pt, const math::Vector3 &_v) | 
| Set a msgs::Vector3d from a math::Vector3.   | |
| void | gazebo::msgs::Set (msgs::Vector2d *_pt, const math::Vector2d &_v) | 
| Set a msgs::Vector2d from a math::Vector3.   | |
| void | gazebo::msgs::Set (msgs::Quaternion *_q, const math::Quaternion &_v) | 
| Set a msgs::Quaternion from a math::Quaternion.   | |
| void | gazebo::msgs::Set (msgs::Pose *_p, const math::Pose &_v) | 
| Set a msgs::Pose from a math::Pose.   | |
| void | gazebo::msgs::Set (msgs::Color *_c, const common::Color &_v) | 
| Set a msgs::Color from a common::Color.   | |
| void | gazebo::msgs::Set (msgs::Time *_t, const common::Time &_v) | 
| Set a msgs::Time from a common::Time.   | |
| void | gazebo::msgs::Set (msgs::PlaneGeom *_p, const math::Plane &_v) | 
| Set a msgs::Plane from a math::Plane.   | |
| void | gazebo::msgs::Stamp (msgs::Header *_header) | 
| Time stamp a header.   | |
| void | gazebo::msgs::Stamp (msgs::Time *_time) | 
| Set the time in a time message.   | |
| msgs::TrackVisual | gazebo::msgs::TrackVisualFromSDF (sdf::ElementPtr _sdf) | 
| Create a msgs::TrackVisual from a track visual SDF element.   | |
| msgs::Visual | gazebo::msgs::VisualFromSDF (sdf::ElementPtr _sdf) | 
| Create a msgs::Visual from a visual SDF element.   | |
All messages and helper functions.
| msgs::Vector3d gazebo::msgs::Convert | ( | const math::Vector3 & | _v | ) | 
Convert a math::Vector3 to a msgs::Vector3d.
| _v | The vector to convert | 
| msgs::Quaternion gazebo::msgs::Convert | ( | const math::Quaternion & | _q | ) | 
Convert a math::Quaternion to a msgs::Quaternion.
| _q | The quaternion to convert | 
| msgs::Pose gazebo::msgs::Convert | ( | const math::Pose & | _p | ) | 
| msgs::Color gazebo::msgs::Convert | ( | const common::Color & | _c | ) | 
Convert a common::Color to a msgs::Color.
| _c | The color to convert | 
| msgs::Time gazebo::msgs::Convert | ( | const common::Time & | _t | ) | 
| msgs::PlaneGeom gazebo::msgs::Convert | ( | const math::Plane & | _p | ) | 
Convert a math::Plane to a msgs::PlaneGeom.
| _p | The plane to convert | 
| math::Vector3 gazebo::msgs::Convert | ( | const msgs::Vector3d & | _v | ) | 
Convert a msgs::Vector3d to a math::Vector.
| _v | The plane to convert | 
| math::Quaternion gazebo::msgs::Convert | ( | const msgs::Quaternion & | _q | ) | 
Convert a msgs::Quaternion to a math::Quaternion.
| _q | The quaternion to convert | 
| math::Pose gazebo::msgs::Convert | ( | const msgs::Pose & | _p | ) | 
| common::Color gazebo::msgs::Convert | ( | const msgs::Color & | _c | ) | 
Convert a msgs::Color to a common::Color.
| _c | The color to convert | 
| common::Time gazebo::msgs::Convert | ( | const msgs::Time & | _t | ) | 
Convert a msgs::Time to a common::Time.
| _t | The time to convert | 
| math::Plane gazebo::msgs::Convert | ( | const msgs::PlaneGeom & | _p | ) | 
Convert a msgs::PlaneGeom to a common::Plane.
| _p | The plane to convert | 
| msgs::Request* gazebo::msgs::CreateRequest | ( | const std::string & | _request, | 
| const std::string & | _data = ""  | 
        ||
| ) | 
Create a request message.
| _request | Request string | 
| _data | Optional data string | 
| msgs::Fog gazebo::msgs::FogFromSDF | ( | sdf::ElementPtr | _sdf | ) | 
Create a msgs::Fog from a fog SDF element.
| _sdf | The sdf element | 
| msgs::Header* gazebo::msgs::GetHeader | ( | google::protobuf::Message & | _message | ) | 
Get the header from a protobuf message.
| _message | A google protobuf message | 
| msgs::GUI gazebo::msgs::GUIFromSDF | ( | sdf::ElementPtr | _sdf | ) | 
Create a msgs::GUI from a GUI SDF element.
| _sdf | The sdf element | 
| void gazebo::msgs::Init | ( | google::protobuf::Message & | _message, | 
| const std::string & | _id = ""  | 
        ||
| ) | 
Initialize a message.
| _message | Message to initialize | 
| _id | Optional string id | 
Referenced by gazebo::physics::HingeJoint< BulletJoint >::Init().
| msgs::Light gazebo::msgs::LightFromSDF | ( | sdf::ElementPtr | _sdf | ) | 
Create a msgs::Light from a light SDF element.
| _sdf | The sdf element | 
| msgs::Scene gazebo::msgs::SceneFromSDF | ( | sdf::ElementPtr | _sdf | ) | 
Create a msgs::Scene from a scene SDF element.
| _sdf | The sdf element | 
| void gazebo::msgs::Set | ( | common::Image & | _img, | 
| const msgs::Image & | _msg | ||
| ) | 
Convert a msgs::Image to a common::Image.
| _img | The common::Image container | 
| _msg | The Image message to convert | 
| void gazebo::msgs::Set | ( | msgs::Image * | _msg, | 
| const common::Image & | _i | ||
| ) | 
Set a msgs::Image from a common::Image.
| _msg | A msgs::Image pointer | 
| _i | A common::Image reference | 
| void gazebo::msgs::Set | ( | msgs::Vector3d * | _pt, | 
| const math::Vector3 & | _v | ||
| ) | 
Set a msgs::Vector3d from a math::Vector3.
| _pt | A msgs::Vector3d pointer | 
| _v | A math::Vector3 reference | 
| void gazebo::msgs::Set | ( | msgs::Vector2d * | _pt, | 
| const math::Vector2d & | _v | ||
| ) | 
Set a msgs::Vector2d from a math::Vector3.
| _pt | A msgs::Vector2d pointer | 
| _v | A math::Vector2d reference | 
| void gazebo::msgs::Set | ( | msgs::Quaternion * | _q, | 
| const math::Quaternion & | _v | ||
| ) | 
Set a msgs::Quaternion from a math::Quaternion.
| _q | A msgs::Quaternion pointer | 
| _v | A math::Quaternion reference | 
| void gazebo::msgs::Set | ( | msgs::Pose * | _p, | 
| const math::Pose & | _v | ||
| ) | 
Set a msgs::Pose from a math::Pose.
| _p | A msgs::Pose pointer | 
| _v | A math::Pose reference | 
| void gazebo::msgs::Set | ( | msgs::Color * | _c, | 
| const common::Color & | _v | ||
| ) | 
Set a msgs::Color from a common::Color.
| _p | A msgs::Color pointer | 
| _v | A common::Color reference | 
| void gazebo::msgs::Set | ( | msgs::Time * | _t, | 
| const common::Time & | _v | ||
| ) | 
Set a msgs::Time from a common::Time.
| _p | A msgs::Time pointer | 
| _v | A common::Time reference | 
| void gazebo::msgs::Set | ( | msgs::PlaneGeom * | _p, | 
| const math::Plane & | _v | ||
| ) | 
Set a msgs::Plane from a math::Plane.
| _p | A msgs::Plane pointer | 
| _v | A math::Plane reference | 
| void gazebo::msgs::Stamp | ( | msgs::Header * | _header | ) | 
Time stamp a header.
| _header | Header to stamp | 
| void gazebo::msgs::Stamp | ( | msgs::Time * | _time | ) | 
Set the time in a time message.
| _time | A Time message | 
| msgs::TrackVisual gazebo::msgs::TrackVisualFromSDF | ( | sdf::ElementPtr | _sdf | ) | 
Create a msgs::TrackVisual from a track visual SDF element.
| _sdf | The sdf element | 
| msgs::Visual gazebo::msgs::VisualFromSDF | ( | sdf::ElementPtr | _sdf | ) | 
Create a msgs::Visual from a visual SDF element.
| _sdf | The sdf element |