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

#include <MAVSubnet.hpp>

Collaboration diagram for MAVSubnet:
Collaboration graph

Public Member Functions

 MAVSubnet (const MAVSubnet &other)=default
 
 MAVSubnet (MAVSubnet &&other)=default
 
 MAVSubnet (const MAVAddress &address, unsigned int mask=0xFFFF)
 
 MAVSubnet (const MAVAddress &address, unsigned int system_mask, unsigned int component_mask)
 
 MAVSubnet (std::string address)
 
bool contains (const MAVAddress &address) const
 
MAVSubnetoperator= (const MAVSubnet &other)=default
 
MAVSubnetoperator= (MAVSubnet &&other)=default
 

Friends

bool operator== (const MAVSubnet &lhs, const MAVSubnet &rhs)
 
bool operator!= (const MAVSubnet &lhs, const MAVSubnet &rhs)
 
std::ostream & operator<< (std::ostream &os, const MAVSubnet &mavsubnet)
 

Detailed Description

A MAVLink subnet.

Mavlink subnets work the same as IP subnets and allow the definition of a range of addresses. This is used to allow a single firewall rule to match multiple addresses.

See also
MAVAddress

Definition at line 36 of file MAVSubnet.hpp.

Constructor & Destructor Documentation

◆ MAVSubnet() [1/5]

MAVSubnet::MAVSubnet ( const MAVSubnet other)
default

Copy constructor.

Parameters
otherMAVLink subnet to copy from.

◆ MAVSubnet() [2/5]

MAVSubnet::MAVSubnet ( MAVSubnet &&  other)
default

Move constructor.

Parameters
otherMAVLink subnet to move from.

◆ MAVSubnet() [3/5]

MAVSubnet::MAVSubnet ( const MAVAddress address,
unsigned int  mask = 0xFFFF 
)

Construct a MAVLink subnet from a MAVLink address and mask.

Parameters
addressMAVLink address of subnet.
maskTwo byte subnet mask, where the system mask is in the MSB and the component mask is in the LSB.
Exceptions
std::out_of_rangeif the mask is not between 0x0000 and 0xFFFF.
See also
Check if a MAVAddress is within the subnet with contains.

Definition at line 38 of file MAVSubnet.cpp.

◆ MAVSubnet() [4/5]

MAVSubnet::MAVSubnet ( const MAVAddress address,
unsigned int  system_mask,
unsigned int  component_mask 
)

Construct MAVLink subnet from an address, system mask, and component mask.

Parameters
addressMAVLink address of subnet.
system_maskOne byte subnet system mask with the bits set that must match the subnet address for a MAVLink address to be contained within the subnet. Valid range is 0 to 255.
component_maskOne byte subnet component mask with the bits set that must match the subnet address for a MAVLink address to be contained within the subnet. Valid range is 0 to 255.
Exceptions
std::out_of_rangeif the system and component masks are not each between 0x00 and 0xFF.
See also
Check if a MAVAddress is within the subnet with contains.

Definition at line 68 of file MAVSubnet.cpp.

◆ MAVSubnet() [5/5]

MAVSubnet::MAVSubnet ( std::string  subnet)

Construct a MAVLink subnet from a string.

There are four string forms of MAVLink subnets:

  1. "<System ID>.<Component ID>:<System ID mask>.<Component ID mask>"
  2. "<System ID>.<Component ID>/<bits>"
  3. "<System ID>.<Component ID>\<bits>"
  4. "<System ID>.<Component ID>"

The first form is self explanatory, but the 2nd and 3rd are not as simple. In the 2nd case the number of bits (0 - 16) is the number of bits from the left that must match for an address to be in the subnet. The 3rd form is like the 2nd, but does not require the system ID (first octet) to match and starts with the number of bits of the component ID (0 - 8) that must match from the left for an address to be in the subnet. The last form is shorthand for "<System ID>.<Component ID>/16", that is an exact match.

Below is a table relating the slash postfix to the subnet mask in <System mask>.<Component mask> notation.

Mask with / Mask with \ Postfix (#bits)
255.255 out of range 16
255.254 out of range 15
255.252 out of range 14
255.248 out of range 13
255.240 out of range 12
255.224 out of range 11
255.192 out of range 10
255.128 out of range 9
255.0 0.255 8
254.0 0.254 7
252.0 0.252 6
248.0 0.248 5
240.0 0.240 4
224.0 0.224 3
192.0 0.192 2
128.0 0.128 1
0.0 0 0

Some examples are:

  • "128.0/8" - Matches addresses with system ID 128 and any component ID.
  • "128.0/9" - Matches addresses with system ID 128 and components ID's of 127 or less.
  • "128.255/9" - Matches addresses with system ID 128 and components ID's of 128 or more.
  • "128.0\1" - Matches addresses any system ID and components ID's of 127 or less.
  • "128.255\1" - Matches addresses any system ID and components ID's of 128 or more.
  • "255.0:128.240" - Matches system ID's 128 or greater and component ID's from 0 to 15.
  • "255.16:128.240" - Matches system ID's 128 or greater and component ID's from 16 to 31.
  • "255.16" - Matches only the address with system ID 255 and component ID 16.
Parameters
subnetString representing the MAVLink subnet.
Exceptions
std::out_of_rangeif either the system ID or the component ID is out of range.
std::out_of_rangeif the mask or slash bits are out of range.
std::invalid_argumentif the subnet string does not represent a valid MAVLink subnet.
See also
Check if a MAVAddress is within the subnet with contains.

Definition at line 161 of file MAVSubnet.cpp.

References MAVAddress::address().

Here is the call graph for this function:

Member Function Documentation

◆ contains()

bool MAVSubnet::contains ( const MAVAddress address) const

Determine whether or not the subnet contains a given MAVLink address.

Parameters
addressThe MAVLink address to test.
Return values
trueif address is part of the subnet.

Definition at line 250 of file MAVSubnet.cpp.

References MAVAddress::address().

Here is the call graph for this function:

◆ operator=() [1/2]

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

Assignment operator.

Parameters
otherMAVLink subnet to copy from.

◆ operator=() [2/2]

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

Assignment operator (by move semantics).

Parameters
otherMAVLink subnet to move from.

Friends And Related Function Documentation

◆ operator!=

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

Inequality comparison.

Compares both address and mask.

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

Definition at line 282 of file MAVSubnet.cpp.

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const MAVSubnet mavsubnet 
)
friend

Print the MAVLink subnet to the given output stream.

There are three string forms of MAVLink subnets.

  1. "<System ID>.<Component ID>:<System ID mask>.<Component ID mask>"
  2. "<System ID>.<Component ID>/<bits>"
  3. "<System ID>.<Component ID>\<bits>"
  4. "<System ID>.<Component ID>"

The slash notation is preferred. The last form is used when the mask requires all bits of a subnet to match an address.

See MAVSubnet::MAVSubnet(std::string address) for more information on the string format.

Note
The string constructor MAVSubnet(std::string) and the output stream operator are not inverses because of form preferences:
Parameters
osThe output stream to print to.
mavsubnetThe MAVLink subnet to print.
Returns
The output stream.

Definition at line 311 of file MAVSubnet.cpp.

◆ operator==

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

Equality comparison.

Compares both address and mask.

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

Definition at line 266 of file MAVSubnet.cpp.


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