30 #ifndef RVIZ_VALIDATE_FLOAT_H
31 #define RVIZ_VALIDATE_FLOAT_H
35 #include <geometry_msgs/PointStamped.h>
36 #include <geometry_msgs/Point32.h>
37 #include <geometry_msgs/Vector3.h>
38 #include <geometry_msgs/PoseStamped.h>
39 #include <geometry_msgs/Twist.h>
40 #include <std_msgs/ColorRGBA.h>
42 #include <OgreQuaternion.h>
44 #include <boost/array.hpp>
50 return !(std::isnan(val) || std::isinf(val));
145 template <
typename T>
148 typedef std::vector<T> VecType;
149 typename VecType::const_iterator it = vec.begin();
150 typename VecType::const_iterator end = vec.end();
151 for (; it != end; ++it)
162 template <
typename T,
size_t N>
165 typedef boost::array<T, N> ArrType;
166 typename ArrType::const_iterator it = arr.begin();
167 typename ArrType::const_iterator end = arr.end();
168 for (; it != end; ++it)
181 #endif // RVIZ_VALIDATE_FLOAT_H