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> 41 #include <OgreVector3.h> 42 #include <OgreQuaternion.h> 44 #include <boost/array.hpp> 51 return !(std::isnan(val) || std::isinf(val));
56 return !(std::isnan(val) || std::isinf(val));
154 typedef std::vector<T> VecType;
155 typename VecType::const_iterator it = vec.begin();
156 typename VecType::const_iterator end = vec.end();
157 for (; it != end; ++it)
168 template<
typename T,
size_t N>
171 typedef boost::array<T, N> ArrType;
172 typename ArrType::const_iterator it = arr.begin();
173 typename ArrType::const_iterator end = arr.end();
174 for (; it != end; ++it)
187 #endif // RVIZ_VALIDATE_FLOAT_H
bool validateFloats(const sensor_msgs::CameraInfo &msg)