|
| 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 | + |
| 25 | + |
| 26 | +// @brief Validation Check |
| 27 | +// Check recieved message is safe or not for the nav2-system |
| 28 | +// For each msg-type known in nav2, we could check it as following: |
| 29 | +// if(!validateMsg()) RCLCPP_ERROR(,"malformed msg. Rejecting.") |
| 30 | +// |
| 31 | +// Workflow of validateMsg(): |
| 32 | +// if here's a sub-msg-type in the recieved msg, |
| 33 | +// the content of sub-msg would be checked as sub-msg-type |
| 34 | +// then, check the whole recieved msg. |
| 35 | +// |
| 36 | +// Following conditions are involved in check: |
| 37 | +// 1> Value Check: to avoid damaged value like like `nan`, `INF`, empty string and so on |
| 38 | +// 2> Logic Check: to avoid value with bad logic, |
| 39 | +// like the size of `map` should be equal to `height*width` |
| 40 | +// 3> Any other needed condition could be joint here in future |
| 41 | + |
| 42 | +namespace nav2_util |
| 43 | +{ |
| 44 | + |
| 45 | + |
| 46 | +bool validateMsg(const double & num) |
| 47 | +{ |
| 48 | + /* @brief double/float value check |
| 49 | + * if here'a need to check message validation |
| 50 | + * it should be avoid to use double value like `nan`, `inf` |
| 51 | + * otherwise, we regard it as an invalid message |
| 52 | + */ |
| 53 | + if (std::isinf(num)) {return false;} |
| 54 | + if (std::isnan(num)) {return false;} |
| 55 | + return true; |
| 56 | +} |
| 57 | + |
| 58 | +const int NSEC_PER_SEC = 1e9; // 1 second = 1e9 nanosecond |
| 59 | +bool validateMsg(const builtin_interfaces::msg::Time & msg) |
| 60 | +{ |
| 61 | + if (msg.nanosec >= NSEC_PER_SEC) { |
| 62 | + return false; // invalid nanosec-stamp |
| 63 | + } |
| 64 | + return true; |
| 65 | +} |
| 66 | + |
| 67 | +bool validateMsg(const std_msgs::msg::Header & msg) |
| 68 | +{ |
| 69 | + // check sub-type |
| 70 | + if (!validateMsg(msg.stamp)) {return false;} |
| 71 | + |
| 72 | + /* @brief frame_id check |
| 73 | + * if here'a need to check message validation |
| 74 | + * it should at least have a non-empty frame_id |
| 75 | + * otherwise, we regard it as an invalid message |
| 76 | + */ |
| 77 | + if (msg.frame_id.empty()) {return false;} |
| 78 | + return true; |
| 79 | +} |
| 80 | + |
| 81 | +bool validateMsg(const geometry_msgs::msg::Point & msg) |
| 82 | +{ |
| 83 | + // check sub-type |
| 84 | + if (!validateMsg(msg.x)) {return false;} |
| 85 | + if (!validateMsg(msg.y)) {return false;} |
| 86 | + if (!validateMsg(msg.z)) {return false;} |
| 87 | + return true; |
| 88 | +} |
| 89 | + |
| 90 | +const double epsilon = 1e-4; |
| 91 | +bool validateMsg(const geometry_msgs::msg::Quaternion & msg) |
| 92 | +{ |
| 93 | + // check sub-type |
| 94 | + if (!validateMsg(msg.x)) {return false;} |
| 95 | + if (!validateMsg(msg.y)) {return false;} |
| 96 | + if (!validateMsg(msg.z)) {return false;} |
| 97 | + if (!validateMsg(msg.w)) {return false;} |
| 98 | + |
| 99 | + if (abs(msg.x * msg.x + msg.y * msg.y + msg.z * msg.z + msg.w * msg.w - 1.0) >= epsilon) { |
| 100 | + return false; |
| 101 | + } |
| 102 | + |
| 103 | + return true; |
| 104 | +} |
| 105 | + |
| 106 | +bool validateMsg(const geometry_msgs::msg::Pose & msg) |
| 107 | +{ |
| 108 | + // check sub-type |
| 109 | + if (!validateMsg(msg.position)) {return false;} |
| 110 | + if (!validateMsg(msg.orientation)) {return false;} |
| 111 | + return true; |
| 112 | +} |
| 113 | + |
| 114 | + |
| 115 | +// Function to verify map meta information |
| 116 | +bool validateMsg(const nav_msgs::msg::MapMetaData & msg) |
| 117 | +{ |
| 118 | + // check sub-type |
| 119 | + if (!validateMsg(msg.origin)) {return false;} |
| 120 | + if (!validateMsg(msg.resolution)) {return false;} |
| 121 | + |
| 122 | + // logic check |
| 123 | + // 1> we don't need an empty map |
| 124 | + if (msg.height == 0 || msg.width == 0) {return false;} |
| 125 | + return true; |
| 126 | +} |
| 127 | + |
| 128 | +// for msg-type like map, costmap and others as `OccupancyGrid` |
| 129 | +bool validateMsg(const nav_msgs::msg::OccupancyGrid & msg) |
| 130 | +{ |
| 131 | + // check sub-type |
| 132 | + if (!validateMsg(msg.header)) {return false;} |
| 133 | + // msg.data : @todo any check for it ? |
| 134 | + if (!validateMsg(msg.info)) {return false;} |
| 135 | + |
| 136 | + // check logic |
| 137 | + if (msg.data.size() != msg.info.width * msg.info.height) { |
| 138 | + return false; // check map-size |
| 139 | + } |
| 140 | + return true; |
| 141 | +} |
| 142 | + |
| 143 | + |
| 144 | +} // namespace nav2_util |
| 145 | + |
| 146 | + |
| 147 | +#endif // NAV2_UTIL__VALIDATE_MESSAGES_HPP_ |
0 commit comments