29 #ifndef MSG_CONVERSIONS_H 30 #define MSG_CONVERSIONS_H 32 #include "OgreVector3.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)
51 o.x = m.x; o.y = m.y; o.z = m.z;
57 return Ogre::Vector3(m.x, m.y, m.z);
63 o.x = m.x; o.y = m.y; o.z = m.z;
69 return Ogre::Quaternion(m.w, m.x, m.y, m.z);
74 o.w = m.w; o.x = m.x; o.y = m.y; o.z = m.z;
78 static inline void pointOgreToMsg(
const Ogre::Vector3 &o, geometry_msgs::Point &m)
80 m.x = o.x; m.y = o.y; m.z = o.z;
85 geometry_msgs::Point m;
93 m.x = o.x; m.y = o.y; m.z = o.z;
98 geometry_msgs::Vector3 m;
106 m.w = o.w; m.x = o.x; m.y = o.y; m.z = o.z;
111 geometry_msgs::Quaternion m;
static void pointOgreToMsg(const Ogre::Vector3 &o, geometry_msgs::Point &m)
static void vector3OgreToMsg(const Ogre::Vector3 &o, geometry_msgs::Vector3 &m)
static Ogre::Vector3 pointMsgToOgre(const geometry_msgs::Point &m)
static Ogre::Quaternion quaternionMsgToOgre(const geometry_msgs::Quaternion &m)
static void quaternionOgreToMsg(const Ogre::Quaternion &o, geometry_msgs::Quaternion &m)
static Ogre::Vector3 vector3MsgToOgre(const geometry_msgs::Vector3 &m)