35 uint8_t autopilot = 2;
36 uint8_t base_mode = 3;
37 uint32_t custom_mode = 4;
38 uint8_t system_status = 5;
39 uint8_t mavlink_version = 6;
42 uint8_t len =
sizeof(payload);
48 uint16_t checksum = 0xFACE;
57 uint64_t time_usec = 295128000000000;
58 uint32_t seq = 0xBA5EBA11;
59 uint8_t target_system = 127;
60 uint8_t target_component = 1;
63 uint8_t len =
sizeof(payload);
69 uint16_t checksum = 0xFACE;
78 uint32_t custom_mode = 2;
79 uint8_t target_system = 123;
80 uint8_t base_mode = 0xFE;
83 uint8_t len =
sizeof(payload);
89 uint16_t checksum = 0xFACE;
94 struct PACKED EncapsulatedDataV1
100 0, 1, 2, 3, 4, 5, 6, 7, 8, 9,
101 10, 11, 12, 13, 14, 15, 16, 17, 18, 19,
102 20, 21, 22, 23, 24, 25, 26, 27, 28, 29,
103 30, 31, 32, 33, 34, 35, 36, 37, 38, 39,
104 40, 41, 42, 43, 44, 45, 46, 47, 48, 49,
105 50, 51, 52, 53, 54, 55, 56, 57, 58, 59,
106 60, 61, 62, 63, 64, 65, 66, 67, 68, 69,
107 70, 71, 72, 73, 74, 75, 76, 77, 78, 79,
108 80, 81, 82, 83, 84, 85, 86, 87, 88, 89,
109 90, 91, 92, 93, 94, 95, 96, 97, 98, 99,
110 100, 101, 102, 103, 104, 105, 106, 107, 108, 109,
111 110, 111, 112, 113, 114, 115, 116, 117, 118, 119,
112 120, 121, 122, 123, 124, 125, 126, 127, 128, 129,
113 130, 131, 132, 133, 134, 135, 136, 137, 138, 139,
114 140, 141, 142, 143, 144, 145, 146, 147, 148, 149,
115 150, 151, 152, 153, 154, 155, 156, 157, 158, 159,
116 160, 161, 162, 163, 164, 165, 166, 167, 168, 169,
117 170, 171, 172, 173, 174, 175, 176, 177, 178, 179,
118 180, 181, 182, 183, 184, 185, 186, 187, 188, 189,
119 190, 191, 192, 193, 194, 195, 196, 197, 198, 199,
120 200, 201, 202, 203, 204, 205, 206, 207, 208, 209,
121 210, 211, 212, 213, 214, 215, 216, 217, 218, 219,
122 220, 221, 222, 223, 224, 225, 226, 227, 228, 229,
123 230, 231, 232, 233, 234, 235, 236, 237, 238, 239,
124 240, 241, 242, 243, 244, 245, 246, 247, 248, 249,
128 uint8_t magic = 0xFE;
132 uint8_t compid = 255;
135 uint16_t checksum = 0xFACE;
140 #pragma clang diagnostic push 141 #pragma clang diagnostic ignored "-Wunused-member-function" 151 uint8_t autopilot = 2;
152 uint8_t base_mode = 3;
153 uint32_t custom_mode = 4;
154 uint8_t system_status = 5;
155 uint8_t mavlink_version = 6;
157 uint8_t magic = 0xFD;
158 uint8_t len =
sizeof(payload);
159 uint8_t incompat_flags = 0;
160 uint8_t compat_flags = 0;
166 uint16_t checksum = 0xFACE;
167 HeartbeatV2() : msgid(0) {}
176 uint64_t time_usec = 295128000000000;
177 uint32_t seq = 0xBA5EBA11;
178 uint8_t target_system = 127;
179 uint8_t target_component = 1;
181 uint8_t magic = 0xFD;
182 uint8_t len =
sizeof(payload);
183 uint8_t incompat_flags = 0;
184 uint8_t compat_flags = 0;
187 uint8_t compid = 168;
190 uint16_t checksum = 0xFACE;
191 PingV2() : msgid(4) {}
200 uint32_t custom_mode = 2;
201 uint8_t target_system = 123;
202 uint8_t base_mode = 0xFD;
204 uint8_t magic = 0xFD;
205 uint8_t len =
sizeof(payload);
206 uint8_t incompat_flags = 0;
207 uint8_t compat_flags = 0;
213 uint16_t checksum = 0xFACE;
214 SetModeV2() : msgid(11) {}
220 struct PACKED MissionSetCurrentV2
228 uint8_t magic = 0xFD;
229 uint8_t len =
sizeof(payload);
230 uint8_t incompat_flags = 0;
231 uint8_t compat_flags = 0;
237 uint16_t checksum = 0xFACE;
238 MissionSetCurrentV2() : msgid(41) {}
243 struct PACKED EncapsulatedDataV2
248 uint8_t data[253] = {
249 0, 1, 2, 3, 4, 5, 6, 7, 8, 9,
250 10, 11, 12, 13, 14, 15, 16, 17, 18, 19,
251 20, 21, 22, 23, 24, 25, 26, 27, 28, 29,
252 30, 31, 32, 33, 34, 35, 36, 37, 38, 39,
253 40, 41, 42, 43, 44, 45, 46, 47, 48, 49,
254 50, 51, 52, 53, 54, 55, 56, 57, 58, 59,
255 60, 61, 62, 63, 64, 65, 66, 67, 68, 69,
256 70, 71, 72, 73, 74, 75, 76, 77, 78, 79,
257 80, 81, 82, 83, 84, 85, 86, 87, 88, 89,
258 90, 91, 92, 93, 94, 95, 96, 97, 98, 99,
259 100, 101, 102, 103, 104, 105, 106, 107, 108, 109,
260 110, 111, 112, 113, 114, 115, 116, 117, 118, 119,
261 120, 121, 122, 123, 124, 125, 126, 127, 128, 129,
262 130, 131, 132, 133, 134, 135, 136, 137, 138, 139,
263 140, 141, 142, 143, 144, 145, 146, 147, 148, 149,
264 150, 151, 152, 153, 154, 155, 156, 157, 158, 159,
265 160, 161, 162, 163, 164, 165, 166, 167, 168, 169,
266 170, 171, 172, 173, 174, 175, 176, 177, 178, 179,
267 180, 181, 182, 183, 184, 185, 186, 187, 188, 189,
268 190, 191, 192, 193, 194, 195, 196, 197, 198, 199,
269 200, 201, 202, 203, 204, 205, 206, 207, 208, 209,
270 210, 211, 212, 213, 214, 215, 216, 217, 218, 219,
271 220, 221, 222, 223, 224, 225, 226, 227, 228, 229,
272 230, 231, 232, 233, 234, 235, 236, 237, 238, 239,
273 240, 241, 242, 243, 244, 245, 246, 247, 248, 249,
277 uint8_t magic = 0xFD;
278 uint8_t len =
sizeof(payload);
279 uint8_t incompat_flags = 0;
280 uint8_t compat_flags = 0;
283 uint8_t compid = 255;
286 uint16_t checksum = 0xFACE;
287 EncapsulatedDataV2() : msgid(131) {}
293 struct PACKED ParamExtRequestListV2
297 uint8_t target_system = 32;
298 uint8_t target_component = 64;
300 uint8_t magic = 0xFD;
301 uint8_t len =
sizeof(payload);
302 uint8_t incompat_flags = 0;
303 uint8_t compat_flags = 0;
306 uint8_t compid = 255;
309 uint16_t checksum = 0xFACE;
310 ParamExtRequestListV2() : msgid(321) {}
314 #pragma clang diagnostic pop 319 #pragma clang diagnostic push 320 #pragma clang diagnostic ignored "-Wunused-template" 325 static std::vector<uint8_t> to_vector(T packet)
327 std::vector<uint8_t> data;
328 data.assign(reinterpret_cast<uint8_t *>(&packet),
329 reinterpret_cast<uint8_t *>(&packet) +
sizeof(packet));
336 static std::vector<uint8_t> to_vector_with_sig(T packet)
338 std::vector<uint8_t> data;
339 packet.incompat_flags |= MAVLINK_IFLAG_SIGNED;
341 data.assign(reinterpret_cast<uint8_t *>(&packet),
342 reinterpret_cast<uint8_t *>(&packet) +
sizeof(packet));
343 std::vector<uint8_t> sig =
345 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13
347 data.insert(std::end(data), std::begin(sig), std::end(sig));
352 #pragma clang diagnostic pop