mavtables  0.2.1
MAVLink router and firewall.
Packet.hpp
Go to the documentation of this file.
1 // MAVLink router and firewall.
2 // Copyright (C) 2018 Michael R. Shannon <mrshannon.aerospace@gmail.com>
3 //
4 // This program is free software; you can redistribute it and/or modify
5 // it under the terms of the GNU General Public License as published by
6 // the Free Software Foundation; either version 2 of the License, or
7 // (at your option) any later version.
8 //
9 // This program is distributed in the hope that it will be useful,
10 // but WITHOUT ANY WARRANTY; without even the implied warranty of
11 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 // GNU General Public License for more details.
13 //
14 // You should have received a copy of the GNU General Public License
15 // along with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 
18 #ifndef PACKET_HPP_
19 #define PACKET_HPP_
20 
21 
22 #include <cstdint>
23 #include <memory>
24 #include <optional>
25 #include <ostream>
26 #include <string>
27 #include <vector>
28 
29 #include "MAVAddress.hpp"
30 
31 
32 class Connection;
33 
34 
35 /** A MAVLink packet.
36  *
37  * This is an abstract class, it is meant to be overridden by classes
38  * implementing either version 1 or version 2 of the MAVLink packet wire
39  * protocol.
40  *
41  * \internal The \ref Version enum must be changed if another packet version is
42  * added.
43  */
44 class Packet
45 {
46  public:
47  enum Version
48  {
49  V1 = 0x0100, //!< MAVLink Version 1.0
50  V2 = 0x0200 //!< MAVLink Version 2.0
51  };
52 
53  /** Copy constructor.
54  *
55  * \param other Packet to copy from.
56  */
57  Packet(const Packet &other) = default;
58  /** Move constructor.
59  *
60  * \param other Packet to move from.
61  */
62  Packet(Packet &&other) = default;
63  Packet(std::vector<uint8_t> data);
64  virtual ~Packet(); // Clang does not like pure virtual destructors.
65  /** Return packet version.
66  *
67  * \returns Two byte Packet version with major version in MSB and minor
68  * version in LSB.
69  */
70  virtual Version version() const = 0;
71  /** Return MAVLink message ID.
72  *
73  * \returns The numeric message ID of the MAVLink packet (0 to 255).
74  */
75  virtual unsigned long id() const = 0;
76  /** Return MAVLink message name.
77  *
78  * \returns The message name of the MAVLink packet.
79  */
80  virtual std::string name() const = 0;
81  /** Return source address.
82  *
83  * Where the packet came from.
84  *
85  * \returns The source MAVLink address of the packet.
86  */
87  virtual MAVAddress source() const = 0;
88  /** Return destination address.
89  *
90  * Where the packet is sent to. This is optional because not all
91  * packets have a destination. %If a system is specified, but not a
92  * component, a component ID of 0 will be used (the broadcast ID).
93  *
94  * \returns The destination MAVLink address of the packet if not a
95  * broadcast packet. %If the packet does not have a destination
96  * address then {} will be returned.
97  */
98  virtual std::optional<MAVAddress> dest() const = 0;
99  void connection(std::weak_ptr<Connection> connection);
100  const std::shared_ptr<Connection> connection() const;
101  const std::vector<uint8_t> &data() const;
102  /** Assignment operator.
103  *
104  * \param other Packet to copy from.
105  */
106  Packet &operator=(const Packet &other) = default;
107  /** Assignment operator (by move semantics).
108  *
109  * \param other Packet to move from.
110  */
111  Packet &operator=(Packet &&other) = default;
112 
113  private:
114  std::vector<uint8_t> data_;
115  std::weak_ptr<Connection> connection_;
116 };
117 
118 
119 bool operator==(const Packet &lhs, const Packet &rhs);
120 bool operator!=(const Packet &lhs, const Packet &rhs);
121 std::ostream &operator<<(std::ostream &os, const Packet &packet);
122 
123 
124 #endif // PACKET_HPP_
Packet & operator=(const Packet &other)=default
virtual unsigned long id() const =0
Packet(const Packet &other)=default
const std::shared_ptr< Connection > connection() const
Definition: Packet.cpp:75
virtual std::optional< MAVAddress > dest() const =0
virtual std::string name() const =0
MAVLink Version 2.0.
Definition: Packet.hpp:50
std::ostream & operator<<(std::ostream &os, const Action &action)
Definition: Action.cpp:188
bool operator==(const Action &lhs, const Action &rhs)
Definition: Action.cpp:154
Version
Definition: Packet.hpp:47
bool operator!=(const Action &lhs, const Action &rhs)
Definition: Action.cpp:168
virtual MAVAddress source() const =0
virtual ~Packet()
Definition: Packet.cpp:42
virtual Version version() const =0
MAVLink Version 1.0.
Definition: Packet.hpp:49
const std::vector< uint8_t > & data() const
Definition: Packet.cpp:52