29 #ifndef MSG_CONVERSIONS_H
30 #define MSG_CONVERSIONS_H
33 #include <OgreQuaternion.h>
35 #include <geometry_msgs/Point.h>
36 #include <geometry_msgs/Vector3.h>
37 #include <geometry_msgs/Quaternion.h>
46 return Ogre::Vector3(m.x, m.y, m.z);
49 static inline void pointMsgToOgre(
const geometry_msgs::Point& m, Ogre::Vector3& o)
59 return Ogre::Vector3(m.x, m.y, m.z);
73 return Ogre::Quaternion(m.w, m.x, m.y, m.z);
85 static inline void pointOgreToMsg(
const Ogre::Vector3& o, geometry_msgs::Point& m)
94 geometry_msgs::Point m;
109 geometry_msgs::Vector3 m;
125 geometry_msgs::Quaternion m;