30 #ifndef RVIZ_VALIDATE_QUATERNIONS_H
31 #define RVIZ_VALIDATE_QUATERNIONS_H
33 #include <geometry_msgs/PoseStamped.h>
34 #include <OgreQuaternion.h>
38 #include <boost/array.hpp>
47 return w * w + x * x + y * y + z * z;
52 if (0.0
f == x && 0.0
f == y && 0.0
f == z && 0.0
f == w)
60 "Quaternion [x: %.3f, y: %.3f, z: %.3f, w: %.3f] not normalized. "
62 x, y, z, w, std::sqrt(norm2));
68 if (0.0
f == x && 0.0
f == y && 0.0
f == z && 0.0
f == w)
74 norm2 = std::sqrt(norm2);
75 float invnorm = 1.0f / norm2;
86 return w * w + x * x + y * y + z * z;
91 if (0.0 == x && 0.0 == y && 0.0 == z && 0.0 == w)
99 "Quaternion [x: %.3f, y: %.3f, z: %.3f, w: %.3f] not normalized. "
101 x, y, z, w, std::sqrt(norm2));
102 return is_normalized;
107 if (0.0 == x && 0.0 == y && 0.0 == z && 0.0 == w)
113 norm2 = std::sqrt(norm2);
114 double invnorm = 1.0 / norm2;
130 return validateQuaternions(quaternion.w(), quaternion.x(), quaternion.y(), quaternion.z());
162 template <
typename T>
165 typedef std::vector<T> VecType;
166 typename VecType::const_iterator it = vec.begin();
167 typename VecType::const_iterator end = vec.end();
168 for (; it != end; ++it)
179 template <
typename T,
size_t N>
182 typedef boost::array<T, N> ArrType;
183 typename ArrType::const_iterator it = arr.begin();
184 typename ArrType::const_iterator end = arr.end();
185 for (; it != end; ++it)
198 #endif // RVIZ_VALIDATE_QUATERNIONS_H