mavtables
0.2.1
MAVLink router and firewall.
|
#include <If.hpp>
Public Member Functions | |
If (std::optional< unsigned long > id={}, std::optional< MAVSubnet > source={}, std::optional< MAVSubnet > dest={}) | |
If (const If &other)=default | |
If (If &&other)=default | |
If & | type (unsigned long id) |
If & | type (const std::string &name) |
If & | from (MAVSubnet subnet) |
If & | from (const std::string &subnet) |
If & | to (MAVSubnet subnet) |
If & | to (const std::string &subnet) |
bool | check (const Packet &packet, const MAVAddress &address) const |
If & | operator= (const If &other)=default |
If & | operator= (If &&other)=default |
Friends | |
bool | operator== (const If &lhs, const If &rhs) |
bool | operator!= (const If &lhs, const If &rhs) |
std::ostream & | operator<< (std::ostream &os, const If &if_) |
An if statement used to determine if a packet matches a rule.
This uses the type, source, and destination of a packet to determine if it matches.
If::If | ( | std::optional< unsigned long > | id = {} , |
std::optional< MAVSubnet > | source = {} , |
||
std::optional< MAVSubnet > | dest = {} |
||
) |
Construct an If statement.
The default is to allow any type of packet from any address to any address.
The type, to, and from methods can be used to apply conditions after construction. Some examples are:
If().type("PING").from("1.0/8").to("255.0");
If().type("HEARTBEAT").from("255.0/8");
If().type("SET_MODE").to("255.0/8");
If().from("255.0/8");
id | The packet ID to match. If {} (std::nullopt) then any packet ID will match. The defaut is {}. |
source | The subnet a source address must be in to match. If {} (std::nullopt) then any source address will match. The default is {}. |
dest | The subnet a destination address must be in to match. If {} (std::nullopt) then any destination address will match. The default is {}. |
std::invalid_argument | if the given id is not valid. |
Definition at line 49 of file If.cpp.
References type().
bool If::check | ( | const Packet & | packet, |
const MAVAddress & | address | ||
) | const |
Check whether a Packet and MAVAddress combination matches.
packet | The packet to check for a match. |
address | The address the packet is to be sent to. |
true | If the packet matches the type, source subnet (by MAVSubnet::contains), and destination subnet (by MAVSubnet::contains) of the if statement. |
false | If any of the packet type, source subnet, or destination subnet does not match. |
Definition at line 160 of file If.cpp.
References Packet::id(), and Packet::source().
Set subnet for source address matching using MAVSubnet.
subnet | The subnet used for source address matching. |
Definition at line 98 of file If.cpp.
If & If::from | ( | const std::string & | subnet | ) |
Set subnet for source address matching by string.
See MAVSubnet::MAVSubnet(std::string address) for the acceptable formats and possible errors.
subnet | The subnet used for source address matching. |
Assignment operator (by move semantics).
other | If to move from. |
Set subnet for destination address matching using MAVSubnet.
subnet | The subnet used for destination address matching. |
Definition at line 127 of file If.cpp.
If & If::to | ( | const std::string & | subnet | ) |
Set subnet for destination address matching by string.
See MAVSubnet::MAVSubnet(std::string address) for the acceptable formats and possible errors.
subnet | The subnet used for destination address matching. |
If & If::type | ( | unsigned long | id | ) |
Set the packet type to match, by ID.
id | The packet ID to match. |
std::invalid_argument | if the given id is not valid. |
Definition at line 69 of file If.cpp.
References mavlink::id(), and mavlink::name().
If & If::type | ( | const std::string & | name | ) |
Set the packet type to match, by name.
name | The packet name to match. |
std::invalid_argument | if the given message name is not valid. |
Definition at line 85 of file If.cpp.
References mavlink::id(), and mavlink::name().
|
friend |