mavtables  0.2.1
MAVLink router and firewall.
If.cpp
Go to the documentation of this file.
1 // MAVLink router and firewall.
2 // Copyright (C) 2018 Michael R. Shannon <mrshannon.aerospace@gmail.com>
3 //
4 // This program is free software; you can redistribute it and/or modify
5 // it under the terms of the GNU General Public License as published by
6 // the Free Software Foundation; either version 2 of the License, or
7 // (at your option) any later version.
8 //
9 // This program is distributed in the hope that it will be useful,
10 // but WITHOUT ANY WARRANTY; without even the implied warranty of
11 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 // GNU General Public License for more details.
13 //
14 // You should have received a copy of the GNU General Public License
15 // along with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 
18 #include <optional>
19 #include <stdexcept>
20 #include <string>
21 #include <utility>
22 
23 #include "If.hpp"
24 #include "mavlink.hpp"
25 #include "MAVSubnet.hpp"
26 #include "Packet.hpp"
27 
28 
29 /** Construct an If statement.
30  *
31  * The default is to allow any type of packet from any address to any address.
32  *
33  * The \ref type, \ref to, and \ref from methods can be used to apply
34  * conditions after construction. Some examples are:
35  * - `%If().type("PING").from("1.0/8").to("255.0");`
36  * - `%If().type("HEARTBEAT").from("255.0/8");`
37  * - `%If().type("SET_MODE").to("255.0/8");`
38  * - `%If().from("255.0/8");`
39  *
40  * \param id The packet ID to match. %If {} (std::nullopt) then any packet ID
41  * will match. The defaut is {}.
42  * \param source The subnet a source address must be in to match. %If {}
43  * (std::nullopt) then any source address will match. The default is {}.
44  * \param dest The subnet a destination address must be in to match. %If {}
45  * (std::nullopt) then any destination address will match. The default is
46  * {}.
47  * \throws std::invalid_argument if the given \p id is not valid.
48  */
50  std::optional<unsigned long> id,
51  std::optional<MAVSubnet> source,
52  std::optional<MAVSubnet> dest)
53  : source_(std::move(source)), dest_(std::move(dest))
54 {
55  if (id)
56  {
57  type(id.value());
58  }
59 }
60 
61 
62 /** Set the packet type to match, by ID.
63  *
64  * \param id The packet ID to match.
65  * \returns A reference to itself.
66  * \throws std::invalid_argument if the given \p id is not valid.
67  * \sa type(const std::string &name)
68  */
69 If &If::type(unsigned long id)
70 {
71  // Check packet ID, throws error if invalid.
72  mavlink::name(id);
73  id_ = id;
74  return *this;
75 }
76 
77 
78 /** Set the packet type to match, by name.
79  *
80  * \param name The packet name to match.
81  * \returns A reference to itself.
82  * \throws std::invalid_argument if the given message \p name is not valid.
83  * \sa type(unsigned long id)
84  */
85 If &If::type(const std::string &name)
86 {
87  id_ = mavlink::id(name);
88  return *this;
89 }
90 
91 
92 /** Set subnet for source address matching using \ref MAVSubnet.
93  *
94  * \param subnet The subnet used for source address matching.
95  * \returns A reference to itself.
96  * \sa from(const std::string &subnet)
97  */
99 {
100  source_ = std::move(subnet);
101  return *this;
102 }
103 
104 
105 /** Set subnet for source address matching by string.
106  *
107  * See \ref MAVSubnet::MAVSubnet(std::string address) for the acceptable
108  * formats and possible errors.
109  *
110  * \param subnet The subnet used for source address matching.
111  * \returns A reference to itself.
112  * \sa from(MAVSubnet subnet)
113  */
114 If &If::from(const std::string &subnet)
115 {
116  source_ = MAVSubnet(subnet);
117  return *this;
118 }
119 
120 
121 /** Set subnet for destination address matching using \ref MAVSubnet.
122  *
123  * \param subnet The subnet used for destination address matching.
124  * \returns A reference to itself.
125  * \sa to(const std::string &subnet)
126  */
128 {
129  dest_ = std::move(subnet);
130  return *this;
131 }
132 
133 
134 /** Set subnet for destination address matching by string.
135  *
136  * See \ref MAVSubnet::MAVSubnet(std::string address) for the acceptable
137  * formats and possible errors.
138  *
139  * \param subnet The subnet used for destination address matching.
140  * \returns A reference to itself.
141  * \sa to(MAVSubnet subnet)
142  */
143 If &If::to(const std::string &subnet)
144 {
145  dest_ = MAVSubnet(subnet);
146  return *this;
147 }
148 
149 
150 /** Check whether a \ref Packet and \ref MAVAddress combination matches.
151  *
152  * \param packet The packet to check for a match.
153  * \param address The address the packet is to be sent to.
154  * \retval true %If the packet matches the type, source subnet (by \ref
155  * MAVSubnet::contains), and destination subnet (by \ref
156  * MAVSubnet::contains) of the if statement.
157  * \retval false %If any of the packet type, source subnet, or destination
158  * subnet does not match.
159  */
160 bool If::check(const Packet &packet, const MAVAddress &address) const
161 {
162  bool result = true;
163 
164  // Check packet ID.
165  if (id_)
166  {
167  result &= packet.id() == id_;
168  }
169 
170  // Check source address.
171  if (source_)
172  {
173  result &= source_->contains(packet.source());
174  }
175 
176  // Check destination address.
177  if (dest_)
178  {
179  result &= dest_->contains(address);
180  }
181 
182  return result;
183 }
184 
185 
186 /** Equality comparison.
187  *
188  * \relates If
189  * \param lhs The left hand side if statement.
190  * \param rhs The right hand side if statement.
191  * \retval true if \p lhs and \p rhs are the same.
192  * \retval false if \p lhs and \p rhs are not the same.
193  */
194 bool operator==(const If &lhs, const If &rhs)
195 {
196  return (lhs.id_ == rhs.id_) && (lhs.source_ == rhs.source_) &&
197  (lhs.dest_ == rhs.dest_);
198 }
199 
200 
201 /** Inequality comparison.
202  *
203  * \relates If
204  * \param lhs The left hand side if statement.
205  * \param rhs The right hand side if statement.
206  * \retval true if \p lhs and \p rhs are not the same.
207  * \retval false if \p lhs and \p rhs are the same.
208  */
209 bool operator!=(const If &lhs, const If &rhs)
210 {
211  return (lhs.id_ != rhs.id_) || (lhs.source_ != rhs.source_) ||
212  (lhs.dest_ != rhs.dest_);
213 }
214 
215 
216 /** Print the \ref If statement to the given output stream.
217  *
218  * Some examples are:
219  * - `if PING from 1.0/8 to 255.0`
220  * - `if HEARTBEAT from 255.0/8`
221  * - `if SET_MODE to 255.0`
222  * - `if from 255.0/8`
223  */
224 std::ostream &operator<<(std::ostream &os, const If &if_)
225 {
226  // Handle the match any if_.
227  os << "if";
228 
229  if (!if_.id_ && !if_.source_ && !if_.dest_)
230  {
231  os << " any";
232  return os;
233  }
234 
235  // Print packet name.
236  if (if_.id_)
237  {
238  os << " " << mavlink::name(if_.id_.value());
239  }
240 
241  // Print source subnet.
242  if (if_.source_)
243  {
244  os << " from " << if_.source_.value();
245  }
246 
247  // Print destination subnet.
248  if (if_.dest_)
249  {
250  os << " to " << if_.dest_.value();
251  }
252 
253  return os;
254 }
If & from(MAVSubnet subnet)
Definition: If.cpp:98
If & type(unsigned long id)
Definition: If.cpp:69
virtual unsigned long id() const =0
If(std::optional< unsigned long > id={}, std::optional< MAVSubnet > source={}, std::optional< MAVSubnet > dest={})
Definition: If.cpp:49
Definition: If.hpp:35
STL namespace.
If & to(MAVSubnet subnet)
Definition: If.cpp:127
std::ostream & operator<<(std::ostream &os, const Action &action)
Definition: Action.cpp:188
bool operator==(const Action &lhs, const Action &rhs)
Definition: Action.cpp:154
bool operator!=(const Action &lhs, const Action &rhs)
Definition: Action.cpp:168
virtual MAVAddress source() const =0
bool check(const Packet &packet, const MAVAddress &address) const
Definition: If.cpp:160