validate_floats.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_VALIDATE_FLOAT_H
31 #define RVIZ_VALIDATE_FLOAT_H
32 
33 #include <cmath>
34 
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>
43 
44 #include <boost/array.hpp>
45 
46 namespace rviz
47 {
48 inline bool validateFloats(Ogre::Real val)
49 {
50  return !(std::isnan(val) || std::isinf(val));
51 }
52 
53 inline bool validateFloats(const Ogre::Vector3& vec)
54 {
55  bool valid = true;
56  valid = valid && validateFloats(vec.x);
57  valid = valid && validateFloats(vec.y);
58  valid = valid && validateFloats(vec.z);
59  return valid;
60 }
61 
62 inline bool validateFloats(const Ogre::Quaternion& quat)
63 {
64  bool valid = true;
65  valid = valid && validateFloats(quat.x);
66  valid = valid && validateFloats(quat.y);
67  valid = valid && validateFloats(quat.z);
68  valid = valid && validateFloats(quat.w);
69  return valid;
70 }
71 
72 inline bool validateFloats(const geometry_msgs::Point& msg)
73 {
74  bool valid = true;
75  valid = valid && validateFloats(msg.x);
76  valid = valid && validateFloats(msg.y);
77  valid = valid && validateFloats(msg.z);
78  return valid;
79 }
80 
81 inline bool validateFloats(const geometry_msgs::Point32& msg)
82 {
83  bool valid = true;
84  valid = valid && validateFloats(msg.x);
85  valid = valid && validateFloats(msg.y);
86  valid = valid && validateFloats(msg.z);
87  return valid;
88 }
89 
90 inline bool validateFloats(const geometry_msgs::Vector3& msg)
91 {
92  bool valid = true;
93  valid = valid && validateFloats(msg.x);
94  valid = valid && validateFloats(msg.y);
95  valid = valid && validateFloats(msg.z);
96  return valid;
97 }
98 
99 inline bool validateFloats(const geometry_msgs::Twist& twist)
100 {
101  bool valid = true;
102  valid = valid && validateFloats(twist.linear);
103  valid = valid && validateFloats(twist.angular);
104  return valid;
105 }
106 
107 inline bool validateFloats(const geometry_msgs::Quaternion& msg)
108 {
109  bool valid = true;
110  valid = valid && validateFloats(msg.x);
111  valid = valid && validateFloats(msg.y);
112  valid = valid && validateFloats(msg.z);
113  valid = valid && validateFloats(msg.w);
114  return valid;
115 }
116 
117 inline bool validateFloats(const std_msgs::ColorRGBA& msg)
118 {
119  bool valid = true;
120  valid = valid && validateFloats(msg.r);
121  valid = valid && validateFloats(msg.g);
122  valid = valid && validateFloats(msg.b);
123  valid = valid && validateFloats(msg.a);
124  return valid;
125 }
126 
127 inline bool validateFloats(const geometry_msgs::PointStamped& msg)
128 {
129  return validateFloats(msg.point);
130 }
131 
132 inline bool validateFloats(const geometry_msgs::Pose& msg)
133 {
134  bool valid = true;
135  valid = valid && validateFloats(msg.position);
136  valid = valid && validateFloats(msg.orientation);
137  return valid;
138 }
139 
140 inline bool validateFloats(const geometry_msgs::PoseStamped& msg)
141 {
142  return validateFloats(msg.pose);
143 }
144 
145 template <typename T>
146 inline bool validateFloats(const std::vector<T>& vec)
147 {
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)
152  {
153  if (!validateFloats(*it))
154  {
155  return false;
156  }
157  }
158 
159  return true;
160 }
161 
162 template <typename T, size_t N>
163 inline bool validateFloats(const boost::array<T, N>& arr)
164 {
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)
169  {
170  if (!validateFloats(*it))
171  {
172  return false;
173  }
174  }
175 
176  return true;
177 }
178 
179 } // namespace rviz
180 
181 #endif // RVIZ_VALIDATE_FLOAT_H
bool validateFloats(const sensor_msgs::CameraInfo &msg)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25