mavtables  0.2.1
MAVLink router and firewall.
Public Types | Public Member Functions | Related Functions | List of all members
packet_v1::Packet Class Reference

#include <PacketVersion1.hpp>

Inheritance diagram for packet_v1::Packet:
Inheritance graph
Collaboration diagram for packet_v1::Packet:
Collaboration graph

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< MAVAddressdest () const
 
Packetoperator= (const Packet &other)=default
 
Packetoperator= (Packet &&other)=default
 
void connection (std::weak_ptr< Connection > connection)
 
const std::shared_ptr< Connectionconnection () 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_headerheader (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)
 

Detailed Description

A MAVLink packet with the version 1 wire protocol.

Definition at line 56 of file PacketVersion1.hpp.

Member Enumeration Documentation

◆ Version

enum Packet::Version
inherited
Enumerator
V1 

MAVLink Version 1.0.

V2 

MAVLink Version 2.0.

Definition at line 47 of file Packet.hpp.

Constructor & Destructor Documentation

◆ Packet() [1/3]

packet_v1::Packet::Packet ( const Packet other)
default

Copy constructor.

Parameters
otherPacket to copy from.

◆ Packet() [2/3]

packet_v1::Packet::Packet ( Packet &&  other)
default

Move constructor.

Parameters
otherPacket to move from.

◆ Packet() [3/3]

Packet::Packet ( std::vector< uint8_t >  data)

Construct a packet.

Parameters
dataRaw packet data.
Exceptions
std::invalid_argumentif packet data does not start with the magic byte (0xFE).
std::length_errorif 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.

Here is the call graph for this function:

Member Function Documentation

◆ connection() [1/2]

void Packet::connection ( std::weak_ptr< Connection connection)
inherited

Set the source connection of the packet.

Parameters
connectionThe source connection.
See also
connection()

Definition at line 63 of file Packet.cpp.

References Packet::connection().

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

◆ connection() [2/2]

const std::shared_ptr< Connection > Packet::connection ( ) const
inherited

Get the source connection of the packet.

Returns
The source connection if set and it still exists, otherwise nullptr.
See also
connection(std::weak_ptr<Connection>)

Definition at line 75 of file Packet.cpp.

Here is the caller graph for this function:

◆ data()

const std::vector< uint8_t > & Packet::data ( ) const
inherited

Return the packet data.

Returns
The packet data as a vector of bytes.

Definition at line 52 of file Packet.cpp.

Here is the caller graph for this function:

◆ dest()

std::optional< MAVAddress > Packet::dest ( ) const
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).

Returns
The destination MAVLink address of the packet if not a broadcast packet. If the packet does not have a destination address then {} will be returned.
Thanks
: The mavlink-router project for an example of how to extract the destination address.

Implements Packet.

Definition at line 146 of file PacketVersion1.cpp.

References Packet::data(), and header().

Here is the call graph for this function:

◆ id()

unsigned long Packet::id ( ) const
virtual

Return MAVLink message ID.

Returns
The numeric message ID of the MAVLink packet (0 to 255).

Implements Packet.

Definition at line 108 of file PacketVersion1.cpp.

References Packet::data(), header(), and mavlink::v1_header::msgid.

Here is the call graph for this function:

◆ name()

std::string Packet::name ( ) const
virtual

Return MAVLink message name.

Returns
The message name of the MAVLink packet.
Exceptions
std::runtime_errorif the packet data has an invalid ID.

Implements Packet.

Definition at line 118 of file PacketVersion1.cpp.

References Packet::data(), and header().

Here is the call graph for this function:

◆ operator=() [1/2]

Packet& packet_v1::Packet::operator= ( const Packet other)
default

Assignment operator.

Parameters
otherPacket to copy from.

◆ operator=() [2/2]

Packet& packet_v1::Packet::operator= ( Packet &&  other)
default

Assignment operator (by move semantics).

Parameters
otherPacket to move from.

◆ source()

MAVAddress Packet::source ( ) const
virtual

Return source address.

Where the packet came from.

Returns
The source MAVLink address of the packet.

Implements Packet.

Definition at line 135 of file PacketVersion1.cpp.

References Packet::data(), and header().

Here is the call graph for this function:

◆ version()

Packet::Version Packet::version ( ) const
virtual

Return packet version.

Returns
Two byte Packet version with major version in MSB and minor version in LSB.
0x0100 (v1.0) - Packet::V1

Implements Packet.

Definition at line 102 of file PacketVersion1.cpp.

References packet_v1::VERSION.

Friends And Related Function Documentation

◆ header()

const struct mavlink::v1_header * header ( const std::vector< uint8_t > &  data)
related

Cast data as a v1.0 packet header structure pointer.

Parameters
dataThe packet data.
Returns
A pointer to the given data, cast to a v1.0 header structure. If an incomplete header is given a nullptr will be returned.

Definition at line 238 of file PacketVersion1.cpp.

References packet_v1::header_complete().

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

◆ header_complete()

bool header_complete ( const std::vector< uint8_t > &  data)
related

Determine if the given data contains a complete v1.0 header.

Parameters
dataThe packet data.
Return values
trueif data contains a complete header (starting with the magic byte).
falseif 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.

Here is the caller graph for this function:

◆ operator!=()

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

Inequality comparison.

Compares the raw packet data.

Parameters
lhsThe left hand side packet.
rhsThe right hand side packet.
Return values
trueif lhs and rhs do not have the same packet data.
falseif lhs and rhs have the same packet data.

Definition at line 107 of file Packet.cpp.

References Packet::data().

Here is the call graph for this function:

◆ operator<<()

std::ostream & operator<< ( std::ostream &  os,
const Packet packet 
)
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)
Parameters
osThe output stream to print to.
packetThe MAVLink packet to print.
Returns
The output stream.

Definition at line 131 of file Packet.cpp.

References Packet::dest(), Packet::id(), Packet::name(), Packet::source(), and Packet::version().

Here is the call graph for this function:

◆ operator==()

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

Equality comparison.

Compares the raw packet data.

Parameters
lhsThe left hand side packet.
rhsThe right hand side packet.
Return values
trueif lhs and rhs have the same packet data.
falseif lhs and rhs do not have the same packet data.

Definition at line 91 of file Packet.cpp.

References Packet::data().

Here is the call graph for this function:

◆ packet_complete()

bool packet_complete ( const std::vector< uint8_t > &  data)
related

Determine if the given data contains a complete v1.0 packet.

Parameters
dataThe packet data.
Return values
trueif data contains a complete packet (starting with the magic byte).
falseif 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.

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

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