Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
validate_messages.hpp
1 // Copyright (c) 2024 GoesM
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 
16 #ifndef NAV2_UTIL__VALIDATE_MESSAGES_HPP_
17 #define NAV2_UTIL__VALIDATE_MESSAGES_HPP_
18 
19 #include <cmath>
20 #include <iostream>
21 
22 #include "nav_msgs/msg/occupancy_grid.hpp"
23 #include "nav_msgs/msg/odometry.hpp"
24 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
25 
26 
27 // @brief Validation Check
28 // Check recieved message is safe or not for the nav2-system
29 // For each msg-type known in nav2, we could check it as following:
30 // if(!validateMsg()) RCLCPP_ERROR(,"malformed msg. Rejecting.")
31 //
32 // Workflow of validateMsg():
33 // if here's a sub-msg-type in the recieved msg,
34 // the content of sub-msg would be checked as sub-msg-type
35 // then, check the whole recieved msg.
36 //
37 // Following conditions are involved in check:
38 // 1> Value Check: to avoid damaged value like like `nan`, `INF`, empty string and so on
39 // 2> Logic Check: to avoid value with bad logic,
40 // like the size of `map` should be equal to `height*width`
41 // 3> Any other needed condition could be joint here in future
42 
43 namespace nav2_util
44 {
45 
46 
47 bool validateMsg(const double & num)
48 {
49  /* @brief double/float value check
50  * if here'a need to check message validation
51  * it should be avoid to use double value like `nan`, `inf`
52  * otherwise, we regard it as an invalid message
53  */
54  if (std::isinf(num)) {return false;}
55  if (std::isnan(num)) {return false;}
56  return true;
57 }
58 
59 template<size_t N>
60 bool validateMsg(const std::array<double, N> & msg)
61 {
62  /* @brief value check for double-array
63  * like the field `covariance` used in the msg-type:
64  * geometry_msgs::msg::PoseWithCovarianceStamped
65  */
66  for (const auto & element : msg) {
67  if (!validateMsg(element)) {return false;}
68  }
69 
70  return true;
71 }
72 
73 const int NSEC_PER_SEC = 1e9; // 1 second = 1e9 nanosecond
74 bool validateMsg(const builtin_interfaces::msg::Time & msg)
75 {
76  if (msg.nanosec >= NSEC_PER_SEC) {
77  return false; // invalid nanosec-stamp
78  }
79  return true;
80 }
81 
82 bool validateMsg(const std_msgs::msg::Header & msg)
83 {
84  // check sub-type
85  if (!validateMsg(msg.stamp)) {return false;}
86 
87  /* @brief frame_id check
88  * if here'a need to check message validation
89  * it should at least have a non-empty frame_id
90  * otherwise, we regard it as an invalid message
91  */
92  if (msg.frame_id.empty()) {return false;}
93  return true;
94 }
95 
96 bool validateMsg(const geometry_msgs::msg::Point & msg)
97 {
98  // check sub-type
99  if (!validateMsg(msg.x)) {return false;}
100  if (!validateMsg(msg.y)) {return false;}
101  if (!validateMsg(msg.z)) {return false;}
102  return true;
103 }
104 
105 const double epsilon = 1e-4;
106 bool validateMsg(const geometry_msgs::msg::Quaternion & msg)
107 {
108  // check sub-type
109  if (!validateMsg(msg.x)) {return false;}
110  if (!validateMsg(msg.y)) {return false;}
111  if (!validateMsg(msg.z)) {return false;}
112  if (!validateMsg(msg.w)) {return false;}
113 
114  if (abs(msg.x * msg.x + msg.y * msg.y + msg.z * msg.z + msg.w * msg.w - 1.0) >= epsilon) {
115  return false;
116  }
117 
118  return true;
119 }
120 
121 bool validateMsg(const geometry_msgs::msg::Pose & msg)
122 {
123  // check sub-type
124  if (!validateMsg(msg.position)) {return false;}
125  if (!validateMsg(msg.orientation)) {return false;}
126  return true;
127 }
128 
129 bool validateMsg(const geometry_msgs::msg::PoseWithCovariance & msg)
130 {
131  // check sub-type
132  if (!validateMsg(msg.pose)) {return false;}
133  if (!validateMsg(msg.covariance)) {return false;}
134 
135  return true;
136 }
137 
138 bool validateMsg(const geometry_msgs::msg::PoseWithCovarianceStamped & msg)
139 {
140  // check sub-type
141  if (!validateMsg(msg.header)) {return false;}
142  if (!validateMsg(msg.pose)) {return false;}
143  return true;
144 }
145 
146 
147 // Function to verify map meta information
148 bool validateMsg(const nav_msgs::msg::MapMetaData & msg)
149 {
150  // check sub-type
151  if (!validateMsg(msg.origin)) {return false;}
152  if (!validateMsg(msg.resolution)) {return false;}
153 
154  // logic check
155  // 1> we don't need an empty map
156  if (msg.height == 0 || msg.width == 0) {return false;}
157  return true;
158 }
159 
160 // for msg-type like map, costmap and others as `OccupancyGrid`
161 bool validateMsg(const nav_msgs::msg::OccupancyGrid & msg)
162 {
163  // check sub-type
164  if (!validateMsg(msg.header)) {return false;}
165  // msg.data : @todo any check for it ?
166  if (!validateMsg(msg.info)) {return false;}
167 
168  // check logic
169  if (msg.data.size() != msg.info.width * msg.info.height) {
170  return false; // check map-size
171  }
172  return true;
173 }
174 
175 
176 } // namespace nav2_util
177 
178 
179 #endif // NAV2_UTIL__VALIDATE_MESSAGES_HPP_