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

#include <MAVAddress.hpp>

Collaboration diagram for MAVAddress:
Collaboration graph

Public Member Functions

 MAVAddress (const MAVAddress &other)=default
 
 MAVAddress (MAVAddress &&other)=default
 
 MAVAddress (unsigned int address)
 
 MAVAddress (unsigned int system, unsigned int component)
 
 MAVAddress (std::string address)
 
unsigned int address () const
 
unsigned int system () const
 
unsigned int component () const
 
MAVAddressoperator= (const MAVAddress &other)=default
 
MAVAddressoperator= (MAVAddress &&other)=default
 

Related Functions

(Note that these are not member functions.)

bool operator== (const MAVAddress &lhs, const MAVAddress &rhs)
 
bool operator!= (const MAVAddress &lhs, const MAVAddress &rhs)
 
bool operator< (const MAVAddress &lhs, const MAVAddress &rhs)
 
bool operator> (const MAVAddress &lhs, const MAVAddress &rhs)
 
bool operator<= (const MAVAddress &lhs, const MAVAddress &rhs)
 
bool operator>= (const MAVAddress &lhs, const MAVAddress &rhs)
 
std::ostream & operator<< (std::ostream &os, const MAVAddress &mavaddress)
 

Detailed Description

A MAVLink address.

MAVLink addresses consist of a system and component and can be represented as two ocetets in the form:

system.component

Therefore, a system ID of 16 and a component ID of 8 can be represented as 16.8.

0.0 is reserved as the broadcast address.

Definition at line 38 of file MAVAddress.hpp.

Constructor & Destructor Documentation

◆ MAVAddress() [1/5]

MAVAddress::MAVAddress ( const MAVAddress other)
default

Copy constructor.

Parameters
otherMAVLink address to copy from.

◆ MAVAddress() [2/5]

MAVAddress::MAVAddress ( MAVAddress &&  other)
default

Move constructor.

Parameters
otherMAVLink address to move from.

◆ MAVAddress() [3/5]

MAVAddress::MAVAddress ( unsigned int  address)

Construct a MAVLink address from an address in numeric representation.

The numeric representation of a MAVLink address is two bytes, the MSB contains the system ID and the LSB contains the component ID.

Parameters
addressAddress (0 - 65535) with system ID encoded in MSB and component ID encoded in LSB.
Exceptions
std::out_of_rangeif the address is not between 0 and 65535.

Definition at line 38 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

◆ MAVAddress() [4/5]

MAVAddress::MAVAddress ( unsigned int  system,
unsigned int  component 
)

Construct a MAVLink address from the system ID and component ID.

Note
component=0 and system=0 is the broadcast address.
Parameters
systemSystem ID (0 - 255).
componentComponent ID (0 - 255).
Exceptions
std::out_of_rangeif either the system ID or the component ID is out of range.

Definition at line 87 of file MAVAddress.cpp.

References component(), and system().

Here is the call graph for this function:

◆ MAVAddress() [5/5]

MAVAddress::MAVAddress ( std::string  address)

Construct MAVLink address from a string.

Parse a string of the form "<System ID>.<Component ID>".

Some examples are:

  • "0.0"
  • "16.8"
  • "128.4"
Parameters
addressString representing the MAVLink address.
Exceptions
std::invalid_argumentif the address string does not represent a valid MAVLink address.
std::out_of_rangeif either the system ID or the component ID is out of range.

Definition at line 108 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

Member Function Documentation

◆ address()

unsigned int MAVAddress::address ( ) const

Return the MAVLink address in numeric form.

Returns
The MAVLink address as a two byte number with the system ID encoded in the MSB and the component ID in the LSB.

Definition at line 151 of file MAVAddress.cpp.

Here is the caller graph for this function:

◆ component()

unsigned int MAVAddress::component ( ) const

Return the Component ID.

Returns
The component ID (0 - 255).

Definition at line 171 of file MAVAddress.cpp.

Here is the caller graph for this function:

◆ operator=() [1/2]

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

Assignment operator.

Parameters
otherMAVLink address to copy from.

◆ operator=() [2/2]

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

Assignment operator (by move semantics).

Parameters
otherMAVLink address to move from.

◆ system()

unsigned int MAVAddress::system ( ) const

Return the System ID.

Returns
The system ID (0 - 255).

Definition at line 161 of file MAVAddress.cpp.

Here is the caller graph for this function:

Friends And Related Function Documentation

◆ operator!=()

bool operator!= ( const MAVAddress lhs,
const MAVAddress rhs 
)
related

Inequality comparison.

Parameters
lhsThe left hand side MAVLink address.
rhsThe right hand side MAVLink address.
Return values
trueif lhs and rhs do not have the same system and component ID's
falseif lhs and rhs have the same system and component ID's.

Definition at line 201 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

◆ operator<()

bool operator< ( const MAVAddress lhs,
const MAVAddress rhs 
)
related

Less than comparison.

Note
The System ID is considered first followed by the Component ID.
Parameters
lhsThe left hand side MAVLink address.
rhsThe right hand side MAVLink address.
Return values
trueif lhs is less than rhs.
falseif lhs is not less than rhs.

Definition at line 217 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

◆ operator<<()

std::ostream & operator<< ( std::ostream &  os,
const MAVAddress mavaddress 
)
related

Print the MAVLink address to the given output stream.

The format is "<System ID>.<Component ID>".

Some examples are:

  • 0.0
  • 16.8
  • 128.4
Note
The string constructor MAVAddress(std::string) and the output stream operator are inverses and thus:
std::string addr = "192.168"
str(MAVAddress(addr)) == addr
Parameters
osThe output stream to print to.
mavaddressThe MAVLink address to print.
Returns
The output stream.

Definition at line 292 of file MAVAddress.cpp.

References component(), and system().

Here is the call graph for this function:

◆ operator<=()

bool operator<= ( const MAVAddress lhs,
const MAVAddress rhs 
)
related

Less than or equal comparison.

Note
The System ID is considered first followed by the Component ID.
Parameters
lhsThe left hand side IP address.
rhsThe right hand side IP address.
Return values
trueif lhs is less than or eqaul to rhs.
falseif lhs is greater than rhs.

Definition at line 249 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

◆ operator==()

bool operator== ( const MAVAddress lhs,
const MAVAddress rhs 
)
related

Equality comparison.

Parameters
lhsThe left hand side MAVLink address.
rhsThe right hand side MAVLink address.
Return values
trueif lhs and rhs have the same system and component ID's.
falseif lhs and rhs do not have the same system and component ID's.

Definition at line 186 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

◆ operator>()

bool operator> ( const MAVAddress lhs,
const MAVAddress rhs 
)
related

Greater than comparison.

Note
The System ID is considered first followed by the Component ID.
Parameters
lhsThe left hand side MAVLink address.
rhsThe right hand side IP address.
Return values
trueif lhs is greater than rhs.
falseif lhs is not greater than rhs.

Definition at line 233 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

◆ operator>=()

bool operator>= ( const MAVAddress lhs,
const MAVAddress rhs 
)
related

Greater than comparison.

Note
The System ID is considered first followed by the Component ID.
Parameters
lhsThe left hand side IP address.
rhsThe right hand side IP address.
Return values
trueif lhs is greater than or equal to rhs.
falseif lhs is less than rhs.

Definition at line 265 of file MAVAddress.cpp.

References address().

Here is the call graph for this function:

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