mavtables
0.2.1
MAVLink router and firewall.
|
#include <Packet.hpp>
Public Types | |
enum | Version { V1 = 0x0100, V2 = 0x0200 } |
Public Member Functions | |
Packet (const Packet &other)=default | |
Packet (Packet &&other)=default | |
Packet (std::vector< uint8_t > data) | |
virtual | ~Packet () |
virtual Version | version () const =0 |
virtual unsigned long | id () const =0 |
virtual std::string | name () const =0 |
virtual MAVAddress | source () const =0 |
virtual std::optional< MAVAddress > | dest () const =0 |
void | connection (std::weak_ptr< Connection > connection) |
const std::shared_ptr< Connection > | connection () const |
const std::vector< uint8_t > & | data () const |
Packet & | operator= (const Packet &other)=default |
Packet & | operator= (Packet &&other)=default |
Related Functions | |
(Note that these are not member functions.) | |
bool | operator== (const Packet &lhs, const Packet &rhs) |
bool | operator!= (const Packet &lhs, const Packet &rhs) |
std::ostream & | operator<< (std::ostream &os, const Packet &packet) |
A MAVLink packet.
This is an abstract class, it is meant to be overridden by classes implementing either version 1 or version 2 of the MAVLink packet wire protocol.
Definition at line 44 of file Packet.hpp.
enum Packet::Version |
Enumerator | |
---|---|
V1 | MAVLink Version 1.0. |
V2 | MAVLink Version 2.0. |
Definition at line 47 of file Packet.hpp.
|
default |
Copy constructor.
other | Packet to copy from. |
Packet::Packet | ( | std::vector< uint8_t > | data | ) |
|
virtual |
Definition at line 42 of file Packet.cpp.
void Packet::connection | ( | std::weak_ptr< Connection > | connection | ) |
Set the source connection of the packet.
connection | The source connection. |
Definition at line 63 of file Packet.cpp.
References connection().
const std::shared_ptr< Connection > Packet::connection | ( | ) | const |
Get the source connection of the packet.
Definition at line 75 of file Packet.cpp.
const std::vector< uint8_t > & Packet::data | ( | ) | const |
Return the packet data.
Definition at line 52 of file Packet.cpp.
|
pure virtual |
Return destination address.
Where the packet is sent to. This is optional because not all packets have a destination. If a system is specified, but not a component, a component ID of 0 will be used (the broadcast ID).
Implemented in packet_v2::Packet, and packet_v1::Packet.
|
pure virtual |
Return MAVLink message ID.
Implemented in packet_v2::Packet, and packet_v1::Packet.
|
pure virtual |
Return MAVLink message name.
Implemented in packet_v2::Packet, and packet_v1::Packet.
Assignment operator.
other | Packet to copy from. |
Assignment operator (by move semantics).
other | Packet to move from. |
|
pure virtual |
Return source address.
Where the packet came from.
Implemented in packet_v2::Packet, and packet_v1::Packet.
|
pure virtual |
Return packet version.
Implemented in packet_v2::Packet, and packet_v1::Packet.
Inequality comparison.
Compares the raw packet data.
lhs | The left hand side packet. |
rhs | The right hand side packet. |
true | if lhs and rhs do not have the same packet data. |
false | if lhs and rhs have the same packet data. |
Definition at line 107 of file Packet.cpp.
References data().
|
related |
Print the packet to the given output stream.
The format is "<Message Name> (#<Message ID>) from <Source Address> to <Destination Address> (v<Packet Version>)". However, "to <Destination Address>" is optional and will not be printed if the destination is the broadcast address 0.0.
Some examples are:
HEARTBEAT (#1) from 16.8 (v1.0)
PING (#4) from 128.4 to 16.8 (v2.0)
DATA_TRANSMISSION_HANDSHAKE (#130) from 16.8 (v2.0)
ENCAPSULATED_DATA (#131) from 128.4 (v2.0)
os | The output stream to print to. |
packet | The MAVLink packet to print. |
Definition at line 131 of file Packet.cpp.
References dest(), id(), name(), source(), and version().
Equality comparison.
Compares the raw packet data.
lhs | The left hand side packet. |
rhs | The right hand side packet. |
true | if lhs and rhs have the same packet data. |
false | if lhs and rhs do not have the same packet data. |
Definition at line 91 of file Packet.cpp.
References data().