Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef MSG_CONVERSIONS_H
00030 #define MSG_CONVERSIONS_H
00031
00032 #include "OgreVector3.h"
00033 #include "OgreQuaternion.h"
00034
00035 #include <geometry_msgs/Point.h>
00036 #include <geometry_msgs/Vector3.h>
00037 #include <geometry_msgs/Quaternion.h>
00038
00039 namespace rviz {
00040
00041
00042
00043
00044 static inline Ogre::Vector3 pointMsgToOgre(const geometry_msgs::Point& m)
00045 {
00046 return Ogre::Vector3(m.x, m.y, m.z);
00047 }
00048
00049 static inline void pointMsgToOgre(const geometry_msgs::Point &m, Ogre::Vector3& o)
00050 {
00051 o.x = m.x; o.y = m.y; o.z = m.z;
00052 }
00053
00054
00055 static inline Ogre::Vector3 vector3MsgToOgre(const geometry_msgs::Vector3& m)
00056 {
00057 return Ogre::Vector3(m.x, m.y, m.z);
00058 }
00059
00060
00061 static inline void vector3MsgToOgre(const geometry_msgs::Vector3 &m, Ogre::Vector3& o)
00062 {
00063 o.x = m.x; o.y = m.y; o.z = m.z;
00064 }
00065
00066
00067 static inline Ogre::Quaternion quaternionMsgToOgre(const geometry_msgs::Quaternion& m)
00068 {
00069 return Ogre::Quaternion(m.w, m.x, m.y, m.z);
00070 }
00071
00072 static inline void quaternionMsgToOgre(const geometry_msgs::Quaternion &m, Ogre::Quaternion& o)
00073 {
00074 o.w = m.w; o.x = m.x; o.y = m.y; o.z = m.z;
00075 }
00076
00077
00078 static inline void pointOgreToMsg(const Ogre::Vector3 &o, geometry_msgs::Point &m)
00079 {
00080 m.x = o.x; m.y = o.y; m.z = o.z;
00081 }
00082
00083 static inline geometry_msgs::Point pointOgreToMsg(const Ogre::Vector3 &o)
00084 {
00085 geometry_msgs::Point m;
00086 pointOgreToMsg(o, m);
00087 return m;
00088 }
00089
00090
00091 static inline void vector3OgreToMsg(const Ogre::Vector3 &o, geometry_msgs::Vector3 &m)
00092 {
00093 m.x = o.x; m.y = o.y; m.z = o.z;
00094 }
00095
00096 static inline geometry_msgs::Vector3 vector3OgreToMsg(const Ogre::Vector3 &o)
00097 {
00098 geometry_msgs::Vector3 m;
00099 vector3OgreToMsg(o, m);
00100 return m;
00101 }
00102
00103
00104 static inline void quaternionOgreToMsg(const Ogre::Quaternion &o, geometry_msgs::Quaternion &m)
00105 {
00106 m.w = o.w; m.x = o.x; m.y = o.y; m.z = o.z;
00107 }
00108
00109 static inline geometry_msgs::Quaternion quaternionOgreToMsg(const Ogre::Quaternion &o)
00110 {
00111 geometry_msgs::Quaternion m;
00112 quaternionOgreToMsg(o, m);
00113 return m;
00114 }
00115
00116
00117 }
00118
00119 #endif