mavtables  0.2.1
MAVLink router and firewall.
Public Member Functions | Friends | List of all members
If Class Reference

#include <If.hpp>

Collaboration diagram for If:
Collaboration graph

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
 
Iftype (unsigned long id)
 
Iftype (const std::string &name)
 
Iffrom (MAVSubnet subnet)
 
Iffrom (const std::string &subnet)
 
Ifto (MAVSubnet subnet)
 
Ifto (const std::string &subnet)
 
bool check (const Packet &packet, const MAVAddress &address) const
 
Ifoperator= (const If &other)=default
 
Ifoperator= (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_)
 

Detailed Description

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.

Definition at line 35 of file If.hpp.

Constructor & Destructor Documentation

◆ If() [1/3]

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");
Parameters
idThe packet ID to match. If {} (std::nullopt) then any packet ID will match. The defaut is {}.
sourceThe subnet a source address must be in to match. If {} (std::nullopt) then any source address will match. The default is {}.
destThe subnet a destination address must be in to match. If {} (std::nullopt) then any destination address will match. The default is {}.
Exceptions
std::invalid_argumentif the given id is not valid.

Definition at line 49 of file If.cpp.

References type().

Here is the call graph for this function:

◆ If() [2/3]

If::If ( const If other)
default

Copy constructor.

Parameters
otherIf to copy from.

◆ If() [3/3]

If::If ( If &&  other)
default

Move constructor.

Parameters
otherIf to move from.

Member Function Documentation

◆ check()

bool If::check ( const Packet packet,
const MAVAddress address 
) const

Check whether a Packet and MAVAddress combination matches.

Parameters
packetThe packet to check for a match.
addressThe address the packet is to be sent to.
Return values
trueIf the packet matches the type, source subnet (by MAVSubnet::contains), and destination subnet (by MAVSubnet::contains) of the if statement.
falseIf 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().

Here is the call graph for this function:

◆ from() [1/2]

If & If::from ( MAVSubnet  subnet)

Set subnet for source address matching using MAVSubnet.

Parameters
subnetThe subnet used for source address matching.
Returns
A reference to itself.
See also
from(const std::string &subnet)

Definition at line 98 of file If.cpp.

Here is the caller graph for this function:

◆ from() [2/2]

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.

Parameters
subnetThe subnet used for source address matching.
Returns
A reference to itself.
See also
from(MAVSubnet subnet)

Definition at line 114 of file If.cpp.

◆ operator=() [1/2]

If& If::operator= ( const If other)
default

Assignment operator.

Parameters
otherIf to copy from.

◆ operator=() [2/2]

If& If::operator= ( If &&  other)
default

Assignment operator (by move semantics).

Parameters
otherIf to move from.

◆ to() [1/2]

If & If::to ( MAVSubnet  subnet)

Set subnet for destination address matching using MAVSubnet.

Parameters
subnetThe subnet used for destination address matching.
Returns
A reference to itself.
See also
to(const std::string &subnet)

Definition at line 127 of file If.cpp.

Here is the caller graph for this function:

◆ to() [2/2]

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.

Parameters
subnetThe subnet used for destination address matching.
Returns
A reference to itself.
See also
to(MAVSubnet subnet)

Definition at line 143 of file If.cpp.

◆ type() [1/2]

If & If::type ( unsigned long  id)

Set the packet type to match, by ID.

Parameters
idThe packet ID to match.
Returns
A reference to itself.
Exceptions
std::invalid_argumentif the given id is not valid.
See also
type(const std::string &name)

Definition at line 69 of file If.cpp.

References mavlink::id(), and mavlink::name().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ type() [2/2]

If & If::type ( const std::string &  name)

Set the packet type to match, by name.

Parameters
nameThe packet name to match.
Returns
A reference to itself.
Exceptions
std::invalid_argumentif the given message name is not valid.
See also
type(unsigned long id)

Definition at line 85 of file If.cpp.

References mavlink::id(), and mavlink::name().

Here is the call graph for this function:

Friends And Related Function Documentation

◆ operator!=

bool operator!= ( const If lhs,
const If rhs 
)
friend

Inequality comparison.

Parameters
lhsThe left hand side if statement.
rhsThe right hand side if statement.
Return values
trueif lhs and rhs are not the same.
falseif lhs and rhs are the same.

Definition at line 209 of file If.cpp.

◆ operator<<

std::ostream& operator<< ( std::ostream &  os,
const If if_ 
)
friend

Print the If statement to the given output stream.

Some examples are:

  • if PING from 1.0/8 to 255.0
  • if HEARTBEAT from 255.0/8
  • if SET_MODE to 255.0
  • if from 255.0/8

Definition at line 224 of file If.cpp.

◆ operator==

bool operator== ( const If lhs,
const If rhs 
)
friend

Equality comparison.

Parameters
lhsThe left hand side if statement.
rhsThe right hand side if statement.
Return values
trueif lhs and rhs are the same.
falseif lhs and rhs are not the same.

Definition at line 194 of file If.cpp.


The documentation for this class was generated from the following files: