mavtables
0.2.1
MAVLink router and firewall.
|
#include <PacketVersion1.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::Version | version () const |
virtual unsigned long | id () const |
virtual std::string | name () const |
virtual MAVAddress | source () const |
virtual std::optional< MAVAddress > | dest () const |
Packet & | operator= (const Packet &other)=default |
Packet & | operator= (Packet &&other)=default |
void | connection (std::weak_ptr< Connection > connection) |
const std::shared_ptr< Connection > | connection () const |
const std::vector< uint8_t > & | data () const |
Related Functions | |
(Note that these are not member functions.) | |
bool | header_complete (const std::vector< uint8_t > &data) |
bool | packet_complete (const std::vector< uint8_t > &data) |
const struct mavlink::v1_header * | header (const std::vector< uint8_t > &data) |
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 with the version 1 wire protocol.
Definition at line 56 of file PacketVersion1.hpp.
|
inherited |
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. |
|
default |
Move constructor.
other | Packet to move from. |
Packet::Packet | ( | std::vector< uint8_t > | data | ) |
Construct a packet.
data | Raw packet data. |
std::invalid_argument | if packet data does not start with the magic byte (0xFE). |
std::length_error | if packet data is either too short or too long. |
Definition at line 41 of file PacketVersion1.cpp.
References packet_v1::CHECKSUM_LENGTH, Packet::data(), header(), header_complete(), packet_v1::HEADER_LENGTH, mavlink::v1_header::len, mavlink::v1_header::msgid, packet_complete(), and packet_v1::START_BYTE.
|
inherited |
Set the source connection of the packet.
connection | The source connection. |
Definition at line 63 of file Packet.cpp.
References Packet::connection().
|
inherited |
Get the source connection of the packet.
Definition at line 75 of file Packet.cpp.
|
inherited |
Return the packet data.
Definition at line 52 of file Packet.cpp.
|
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).
Implements Packet.
Definition at line 146 of file PacketVersion1.cpp.
References Packet::data(), and header().
|
virtual |
Return MAVLink message ID.
Implements Packet.
Definition at line 108 of file PacketVersion1.cpp.
References Packet::data(), header(), and mavlink::v1_header::msgid.
|
virtual |
Return MAVLink message name.
std::runtime_error | if the packet data has an invalid ID. |
Implements Packet.
Definition at line 118 of file PacketVersion1.cpp.
References Packet::data(), and header().
Assignment operator.
other | Packet to copy from. |
Assignment operator (by move semantics).
other | Packet to move from. |
|
virtual |
Return source address.
Where the packet came from.
Implements Packet.
Definition at line 135 of file PacketVersion1.cpp.
References Packet::data(), and header().
|
virtual |
Return packet version.
Implements Packet.
Definition at line 102 of file PacketVersion1.cpp.
References packet_v1::VERSION.
|
related |
Cast data as a v1.0 packet header structure pointer.
data | The packet data. |
Definition at line 238 of file PacketVersion1.cpp.
References packet_v1::header_complete().
|
related |
Determine if the given data contains a complete v1.0 header.
data | The packet data. |
true | if data contains a complete header (starting with the magic byte). |
false | if data does not contain a complete v1.0 header. |
Definition at line 200 of file PacketVersion1.cpp.
References packet_v1::HEADER_LENGTH, and packet_v1::START_BYTE.
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 Packet::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 Packet::dest(), Packet::id(), Packet::name(), Packet::source(), and Packet::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 Packet::data().
|
related |
Determine if the given data contains a complete v1.0 packet.
data | The packet data. |
true | if data contains a complete packet (starting with the magic byte). |
false | if data does not contain a complete v1.0 packet, or if there is extra bytes in data beyond the packet. |
Definition at line 218 of file PacketVersion1.cpp.
References packet_v1::CHECKSUM_LENGTH, packet_v1::header(), packet_v1::header_complete(), packet_v1::HEADER_LENGTH, and mavlink::v1_header::len.