mavio 0.5.10

Minimalistic MAVLink client that supports `no-std` and `no-alloc` targets.
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
1312
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
//! # MAVLink frame

use crc_any::CRCu16;

use crate::consts::{CHECKSUM_SIZE, SIGNATURE_LENGTH};
use crate::error::{ChecksumError, SignatureError, VersionError};
use crate::io::{AsyncRead, AsyncWrite, Read, Write};
use crate::protocol::header::Header;
use crate::protocol::marker::{
    HasCompId, HasMsgId, HasPayload, HasPayloadLen, HasSysId, Sequenced, Unset,
};
use crate::protocol::signature::{Sign, Signature, Signer, SigningConf};
use crate::protocol::{
    Checksum, CompatFlags, ComponentId, CrcExtra, FrameBuilder, IncompatFlags, MavLinkVersion,
    MavTimestamp, MessageId, Payload, PayloadLength, SecretKey, Sequence, SignatureBytes,
    SignedLinkId, SystemId,
};

use crate::prelude::*;

/// MAVLink frame.
///
/// Represents [`MAVLink1`](https://mavlink.io/en/guide/serialization.html#v1_packet_format) or
/// [`MAVLink2`](https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format) packet.
///
/// # Protocol Version
///
/// All MAVLink frames always belong to a specific MAVLink protocol version. However, for the
/// sake of generality, this library provides a way to deal with MAVLink protocol version both
/// explicitly by operating on [`Frame<V1>`] / [`Frame<V2>`] and implicitly through
/// [`Frame<Versionless>`]. The latter can be obtained by [`Frame::into_versionless`]
/// and converted into a protocol-specific form through [`Frame::try_into_versioned`]. Both
/// versionless and versioned forms of a frame could be correctly decoded into the corresponding
/// MAVLink message.
///
/// # Encoding / Decoding
///
/// Frames can be decoded into the corresponding MAVLink message by the [`Frame::decode`] method.
/// This requires an appropriate MAVLink dialect to be generated by [`mavspec`]. All autogenerated
/// dialects can be found in the [`mavio::dialects`](crate::dialects) module.
///
/// To encode MAVLink message into a frame, you should use [`FrameBuilder::message`] as described in
/// the [construction](#construction) section.
///
/// # Construction
///
/// Since MAVLink frame has a complex internal structure that depends on [`MavLinkVersion`],
/// encoded [`Message`] and presence of [`Signature`], there is no a direct constructor for this
/// struct. [`Frame`] can be either received as they were sent by remote or built from [`FrameBuilder`].
///
/// Use [`Frame::builder`] to create new frames via builder and [`Frame::add_signature`] (for
/// [`Frame<V2>`] only) to sign frames.
///
/// # Serialization / Deserialization
///
/// When you have no other options but to deal with byte representation of MAVLink frames, you can
/// use [`Frame::serialize`] / [`Frame::deserialize`].
#[derive(Clone, Debug)]
#[cfg_attr(feature = "specta", derive(specta::Type))]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct Frame<V: MaybeVersioned> {
    pub(super) header: Header<V>,
    pub(super) payload: Payload,
    pub(super) checksum: Checksum,
    pub(super) signature: Option<Signature>,
}

impl Frame<Versionless> {
    /// Instantiates an empty builder for [`Frame`].
    pub fn builder(
    ) -> FrameBuilder<Versionless, Unset, Unset, Unset, Unset, Unset, Unset, Unset, Unset> {
        FrameBuilder::new()
    }
}

///////////////////////////////////////////////////////////////////////////////
//                                    ALL                                    //
///////////////////////////////////////////////////////////////////////////////
impl<V: MaybeVersioned> Frame<V> {
    /// Frame [`Header`].
    #[inline]
    pub fn header(&self) -> &Header<V> {
        &self.header
    }

    /// MAVLink protocol version defined by [`Header`].
    ///
    /// # Links
    ///
    /// * [`MavLinkVersion`]
    /// * [`Header::version`]
    /// * [`MavFrame::version`]
    #[inline]
    pub fn version(&self) -> MavLinkVersion {
        self.header.version()
    }

    /// Payload length.
    ///
    /// Indicates length of the following `payload` section. This may be affected by payload truncation.
    ///
    /// # Links
    ///
    /// * [`Header::payload_length`].
    /// * [`MavFrame::payload_length`].
    #[inline]
    pub fn payload_length(&self) -> PayloadLength {
        self.header.payload_length()
    }

    /// Packet sequence number.
    ///
    /// Used to detect packet loss. Components increment value for each message sent.
    ///
    /// # Links
    ///
    /// * [`Header::sequence`].
    /// * [`MavFrame::sequence`]
    #[inline]
    pub fn sequence(&self) -> Sequence {
        self.header.sequence()
    }

    /// System `ID`.
    ///
    /// `ID` of system (vehicle) sending the message. Used to differentiate systems on network.
    ///
    /// > Note that the broadcast address 0 may not be used in this field as it is an invalid source
    /// > address.
    ///
    /// # Links
    ///
    /// * [`Header::system_id`].
    /// * [`MavFrame::system_id`].
    #[inline]
    pub fn system_id(&self) -> SystemId {
        self.header.system_id()
    }

    /// Component `ID`.
    ///
    /// `ID` of component sending the message. Used to differentiate components in a system (e.g.
    /// autopilot and a camera). Use appropriate values in
    /// [MAV_COMPONENT](https://mavlink.io/en/messages/common.html#MAV_COMPONENT).
    ///
    /// > Note that the broadcast address `MAV_COMP_ID_ALL` may not be used in this field as it is
    /// > an invalid source address.
    ///
    /// # Links
    ///
    /// * [`Header::component_id`].
    /// * [`MavFrame::component_id`].
    #[inline]
    pub fn component_id(&self) -> ComponentId {
        self.header.component_id()
    }

    /// Message `ID`.
    ///
    /// `ID` of MAVLink message. Defines how payload will be encoded and decoded.
    ///
    /// # Links
    ///
    /// * [`Header::message_id`].
    /// * [`MavFrame::message_id`].
    #[inline]
    pub fn message_id(&self) -> MessageId {
        self.header.message_id()
    }

    /// Payload data.
    ///
    /// Message data. Content depends on message type (i.e. `message_id`).
    ///
    /// Returns an instance of [`Payload`]. If you are interested in payload bytes, use
    /// [`Payload::bytes`].
    ///
    /// # Links
    ///
    /// * [`MavFrame::payload`].
    #[inline]
    pub fn payload(&self) -> &Payload {
        &self.payload
    }

    /// MAVLink packet checksum.
    ///
    /// `CRC-16/MCRF4XX` [checksum](https://mavlink.io/en/guide/serialization.html#checksum) for
    /// message (excluding magic byte).
    ///
    /// Includes [CRC_EXTRA](https://mavlink.io/en/guide/serialization.html#crc_extra) byte.
    ///
    /// Checksum is encoded with little endian (low byte, high byte).
    ///
    /// # Links
    ///
    /// * [`Frame::calculate_crc`] for implementation.
    /// * [MAVLink checksum definition](https://mavlink.io/en/guide/serialization.html#checksum).
    /// * [CRC-16/MCRF4XX](https://ww1.microchip.com/downloads/en/AppNotes/00752a.pdf) (PDF).
    /// * [`MavFrame::checksum`]
    #[inline]
    pub fn checksum(&self) -> Checksum {
        self.checksum
    }

    /// Returns `true` if frame is signed.
    ///
    /// Returns `true` if [`Frame`] contains [`Signature`]. Correctness of signature is not validated.
    ///
    /// For `MAVLink 1` frames always returns `false`.
    ///
    /// # Links
    ///
    /// * [`MavFrame::is_signed`]
    #[inline]
    pub fn is_signed(&self) -> bool {
        self.signature.is_some()
    }

    /// `MAVLink 2` signature.
    ///
    /// Returns signature that ensures the link is tamper-proof.
    ///
    /// Available only for signed `MAVLink 2` frames. For `MAVLink 1` always return `None`.
    ///
    /// # Links
    ///
    /// * [`Frame::is_signed`] checks that frame is signed.
    /// * [`Frame::link_id`] and [`Frame::timestamp`] provide direct access to signature fields
    ///   ([`Frame<V2>`] only).
    /// # [`MavFrame::signature`].
    /// * [MAVLink 2 message signing](https://mavlink.io/en/guide/message_signing.html).
    #[inline]
    pub fn signature(&self) -> Option<&Signature> {
        if self.matches_version(V2) {
            self.signature.as_ref()
        } else {
            None
        }
    }

    /// Removes `MAVLink 2` signature from frame.
    ///
    /// Applicable only for `MAVLink 2` frames. `MAVLink 1` frames will be kept untouched.
    ///
    /// # Links
    ///
    /// [`MavFrame::remove_signature`]
    pub fn remove_signature(&mut self) {
        self.signature = None;
        self.header.set_is_signed(false)
    }

    /// Frame size in bytes when serialized.
    ///
    /// > Note that the size of a deserialized frame is not equal to the occupied memory.
    ///
    /// # Links
    ///
    /// * [`Header::size`] returns header size in bytes when serialized.
    /// * [`Frame::body_length`] returns frame body length in bytes.
    #[inline]
    pub fn size(&self) -> usize {
        self.header.size() + self.body_length()
    }

    /// Body length.
    ///
    /// Returns the length of the entire [`Frame`] body. The frame body consist of [`Payload::bytes`], [`Checksum`], and
    /// optional [`Signature`] (for `MAVLink 2` protocol).
    ///
    /// # Links
    ///
    /// * [`Header::body_length`].
    /// * [`MavFrame::body_length`].
    #[inline]
    pub fn body_length(&self) -> usize {
        self.header().body_length()
    }

    /// Calculates CRC for frame within `crc_extra`.
    ///
    /// Provided `crc_extra` depends on a dialect and contains a digest of message XML definition.
    ///
    /// # Links
    ///
    /// * [`Frame::checksum`].
    /// * [`MavFrame::calculate_crc`].
    /// * [MAVLink checksum definition](https://mavlink.io/en/guide/serialization.html#checksum).
    /// * [CRC-16/MCRF4XX](https://ww1.microchip.com/downloads/en/AppNotes/00752a.pdf) (PDF).
    pub fn calculate_crc(&self, crc_extra: CrcExtra) -> Checksum {
        let mut crc_calculator = CRCu16::crc16mcrf4cc();

        crc_calculator.digest(self.header.serialize().crc_data());
        crc_calculator.digest(self.payload.bytes());

        crc_calculator.digest(&[crc_extra]);

        crc_calculator.get_crc()
    }

    /// Validates frame in the context of specific dialect.
    ///
    /// Receives dialect specification in `dialect_spec`, ensures that message with such ID
    /// exists in this dialect, and compares checksums using `EXTRA_CRC`.
    ///
    /// # Errors
    ///
    /// * Returns [`Error::Spec`] if message discovery failed.
    /// * Returns [`FrameError::Checksum`] (wrapped by [`Error`]) if checksum
    ///   validation failed.
    ///
    /// # Links
    ///
    /// * [`Dialect`] for dialect specification.
    /// * [`Frame::calculate_crc`] for CRC implementation details.
    /// * [`MavFrame::validate_checksum`].
    pub fn validate_checksum<D: Dialect>(&self) -> Result<()> {
        let message_info = D::message_info(self.header().message_id())?;
        self.validate_checksum_with_crc_extra(message_info.crc_extra())?;

        Ok(())
    }

    /// Validates frame's checksum using provided `crc_extra`.
    ///
    /// # Errors
    ///
    /// Returns [`ChecksumError`] if checksum validation failed.
    ///
    /// # Links
    ///
    /// * [`Frame::calculate_crc`] for CRC implementation details.
    /// * [`MavFrame::validate_checksum_with_crc_extra`].
    pub fn validate_checksum_with_crc_extra(
        &self,
        crc_extra: CrcExtra,
    ) -> core::result::Result<(), ChecksumError> {
        if self.calculate_crc(crc_extra) != self.checksum {
            return Err(ChecksumError);
        }

        Ok(())
    }

    /// Checks that frame has MAVLink version equal to the provided one.
    ///
    /// # Links
    ///
    /// # [`MavFrame::matches_version`]
    pub fn matches_version<Version: Versioned>(
        &self,
        #[allow(unused_variables)] version: Version,
    ) -> bool {
        Version::matches(self.version())
    }

    /// Attempts to transform frame into its versioned form.
    ///
    /// This method never changes the internal MAVLink protocol version. It will return an error,
    /// if conversion is not possible.
    pub fn try_into_versioned<Version: MaybeVersioned>(
        self,
    ) -> core::result::Result<Frame<Version>, VersionError> {
        Version::expect(self.version())?;

        Ok(Frame {
            header: self.header.try_into_versioned::<Version>()?,
            payload: self.payload,
            checksum: self.checksum,
            signature: self.signature,
        })
    }

    /// Attempts to create frame of specified version from the existing one.
    ///
    /// This method never changes the internal MAVLink protocol version. It will return an error,
    /// if conversion is not possible.
    pub fn try_to_versioned<Version: MaybeVersioned>(
        &self,
    ) -> core::result::Result<Frame<Version>, VersionError> {
        self.clone().try_into_versioned()
    }

    /// Forget about the frame's version transforming it into a [`Versionless`] variant.
    pub fn into_versionless(self) -> Frame<Versionless> {
        Frame {
            header: self.header.into_versionless(),
            payload: self.payload,
            checksum: self.checksum,
            signature: self.signature,
        }
    }

    /// Forget about frame's version transforming it into a [`Versionless`] variant.
    pub fn to_versionless(&self) -> Frame<Versionless> {
        self.clone().into_versionless()
    }

    /// Converts this frame into a dynamic [`MavFrame`].
    pub fn into_mav_frame(self) -> MavFrame {
        MavFrame::new(self)
    }

    /// Decodes the frame into a message of a particular MAVLink dialect.
    ///
    /// Performs [`Frame::checksum`] validation before returning the decoded message.
    ///
    /// # Usage
    ///
    /// ```rust,no_run
    /// # #[cfg(feature = "dlct-minimal")] {
    /// # use minimal::messages::Heartbeat;
    /// # use mavio::protocol::{V2};
    /// use mavio::dialects::minimal;
    /// use mavio::dialects::minimal::Minimal;
    /// use mavio::Frame;
    ///
    /// let frame = // ... obtain a frame
    /// #     Frame::builder()
    /// #         .sequence(0)
    /// #         .system_id(1)
    /// #         .component_id(1)
    /// #         .version(V2)
    /// #         .message(&Heartbeat::default()).unwrap()
    /// #         .build();
    ///
    /// // Decode the frame within `minimal` dialect and match the result over available dialect messages
    /// match frame.decode().unwrap() {
    ///     Minimal::Heartbeat(message) => {
    ///         /* process heartbeat message */
    ///     }
    ///     _ => unreachable!()
    /// }
    /// # }
    /// ```
    ///
    /// This function is useful when you are expecting to receive any message withing a particular
    /// dialect into an option of the dialect enum (such as [Minimal](crate::dialects::Minimal)).
    /// This introduces a slight memory overhead due to the way how Rust enums are stored. If
    /// instead, you want to decode a particular message directly, use [`Frame::decode_message`].
    ///
    /// # Errors
    ///
    /// * Returns [`FrameError::Checksum`] if checksum validation failed.
    /// * Returns [`Error::Spec`] if the frame can't be correctly decoded to the provided
    ///   [`Dialect`] (generic type argument).
    ///
    /// # Links
    ///
    /// * [`Frame::decode_message`] decodes the frame into a particular message directly.
    /// * [`Frame::validate_checksum_with_crc_extra`] performs checksum validation.
    /// * [`SpecError`] contains errors related to MAVLink dialect specification and message
    ///   encoding/decoding.
    #[inline]
    pub fn decode<D: Dialect>(&self) -> Result<D> {
        let message = D::decode(self.payload()).map_err(Error::from)?;
        self.validate_checksum_with_crc_extra(message.crc_extra())?;
        Ok(message)
    }

    /// Decodes the frame into a particular MAVLink message.
    ///
    /// Performs [`Frame::checksum`] validation before returning the decoded message.
    ///
    /// # Usage
    ///
    /// ```rust,no_run
    /// # #[cfg(feature = "dlct-minimal")] {
    /// # use mavio::protocol::{V2};
    /// use mavio::dialects::minimal;
    /// use mavio::Frame;
    /// use minimal::messages::Heartbeat;
    ///
    /// let frame = // ... obtain a frame
    /// #     Frame::builder()
    /// #         .sequence(0)
    /// #         .system_id(1)
    /// #         .component_id(1)
    /// #         .version(V2)
    /// #         .message(&Heartbeat::default()).unwrap()
    /// #         .build();
    ///
    /// // Decode the frame into a specific type based on its `ID`
    /// match frame.message_id() {
    ///     Heartbeat::ID => {
    ///         let message = frame.decode_message::<Heartbeat>().unwrap();
    ///     }
    ///     _ => unreachable!()
    /// }
    /// # }
    /// ```
    ///
    /// This function is useful when you know exactly what message you want to decode. You may also
    /// want to consider using [`Frame::decode`] that decodes any valid message into a dialect enum.
    ///
    /// # Errors
    ///
    /// * Returns [`FrameError::Checksum`] if checksum validation failed.
    /// * Returns [`Error::Spec`] if the frame can't be correctly decoded to the desired message.
    ///
    /// # Links
    ///
    /// * [`Frame::decode`] decodes the frame into a message as on option of the particular dialect
    ///   enum.
    /// * [`Frame::validate_checksum_with_crc_extra`] performs checksum validation.
    /// * [`SpecError`] contains errors related to MAVLink dialect specification and message
    ///   encoding/decoding.
    #[inline]
    pub fn decode_message<
        'a,
        M: mavspec::rust::spec::MessageSpecStatic + TryFrom<&'a Payload, Error = SpecError>,
    >(
        &'a self,
    ) -> Result<M> {
        self.validate_checksum_with_crc_extra(M::crc_extra())?;
        let message = M::try_from(self.payload()).map_err(Error::from)?;
        Ok(message)
    }

    /// Upgrades the frame in-place to `MAVLink 2` protocol version using provided `CRC_EXTRA`.
    ///
    /// The opposite is not possible since we need to know the exact payload length.
    pub fn upgrade_with_crc_extra(&mut self, crc_extra: CrcExtra) {
        self.payload.upgrade();
        self.header.payload_length = self.payload.length();
        self.checksum = self.calculate_crc(crc_extra);
    }

    /// Serializes the frame into a sequence of bytes.
    ///
    /// Accepts a mutable buffer and writes the frame into it, returning the number of bytes
    /// written.
    ///
    /// The buffer should be large enough, otherwise [FrameError::FrameBufferIsTooSmall] error will be
    /// returned.
    ///
    /// # Errors
    ///
    /// Returns [FrameError::FrameBufferIsTooSmall] if the provided buffer is too small.
    ///
    /// # Links
    ///
    /// * [Frame::deserialize] to deserialize a frame from a buffer.
    /// * [Frame::size] returns frame size in bytes.
    pub fn serialize(&self, buf: &mut [u8]) -> core::result::Result<usize, FrameError> {
        if buf.len() < self.size() {
            return Err(FrameError::FrameBufferIsTooSmall {
                expected: self.size(),
                actual: buf.len(),
            });
        }

        let header_bytes = self.header.serialize();
        let header_bytes_slice = header_bytes.as_slice();

        buf[0..header_bytes_slice.len()].copy_from_slice(header_bytes_slice);

        let body_bytes = &mut buf[header_bytes_slice.len()..];
        self.fill_body_buffer(body_bytes);

        Ok(self.size())
    }

    /// Deserializes a frame from a sequence of bytes.
    ///
    /// > This function is marked as unsafe since construction of frames from an arbitrary sequence
    /// > of bytes is considered as a potentially risky practice. Yet the implementation contains
    /// > only a sound and safe Rust code.
    ///
    /// The buffer should have a sufficient size and should start from a magic byte. Otherwise, an
    /// error will be returned.
    ///
    /// # Errors
    ///
    /// * Returns [FrameError::InvalidHeader] if the sequence doesn't start with a valid header.
    /// * Returns [FrameError::FrameBufferIsTooSmall] if the buffer does not contain an exact
    ///   representation of a frame.
    ///
    /// # Links
    ///
    /// * [Frame::serialize] to serialize a frame into a buffer.
    pub unsafe fn deserialize(buf: &[u8]) -> core::result::Result<Frame<V>, FrameError> {
        let header = Header::<V>::deserialize(buf)?;

        let frame_length = header.size() + header.body_length();

        if buf.len() < frame_length {
            return Err(FrameError::FrameBufferIsTooSmall {
                expected: frame_length,
                actual: buf.len(),
            });
        }

        let body_bytes = &buf[header.size()..];
        let frame = Self::from_raw_body(header, body_bytes);

        Ok(frame)
    }

    pub(crate) fn recv<E: Into<Error>, R: Read<E>>(
        reader: &mut R,
    ) -> core::result::Result<Frame<V>, E> {
        let header = Header::<V>::recv(reader)?;
        let body_length = header.body_length();

        #[cfg(feature = "std")]
        let mut body_buf = vec![0u8; body_length];
        #[cfg(not(feature = "std"))]
        let mut body_buf =
            [0u8; crate::consts::PAYLOAD_MAX_SIZE + CHECKSUM_SIZE + SIGNATURE_LENGTH];
        let body_bytes = &mut body_buf[0..body_length];

        reader.read_exact(body_bytes)?;
        let frame = Self::from_raw_body(header, body_bytes);

        Ok(frame)
    }

    pub(crate) async fn recv_async<E: Into<Error>, R: AsyncRead<E>>(
        reader: &mut R,
    ) -> core::result::Result<Frame<V>, E> {
        let header = Header::<V>::recv_async(reader).await?;
        let body_length = header.body_length();

        #[cfg(feature = "std")]
        let mut body_buf = vec![0u8; body_length];
        #[cfg(not(feature = "std"))]
        let mut body_buf =
            [0u8; crate::consts::PAYLOAD_MAX_SIZE + CHECKSUM_SIZE + SIGNATURE_LENGTH];
        let body_bytes = &mut body_buf[0..body_length];

        reader.read_exact(body_bytes).await?;
        let frame = Self::from_raw_body(header, body_bytes);

        Ok(frame)
    }

    pub(crate) fn send<E: Into<Error>, W: Write<E>>(
        &self,
        writer: &mut W,
    ) -> core::result::Result<usize, E> {
        let header_bytes_sent = self.header.send(writer)?;

        #[cfg(not(feature = "alloc"))]
        let mut buf = [0u8; crate::consts::PAYLOAD_MAX_SIZE + SIGNATURE_LENGTH];
        #[cfg(feature = "alloc")]
        let mut buf = alloc::vec![0u8; self.body_length()];
        let body_bytes = &mut buf[..self.body_length()];

        self.fill_body_buffer(body_bytes);
        writer.write_all(body_bytes)?;

        Ok(header_bytes_sent + self.body_length())
    }

    pub(crate) async fn send_async<E: Into<Error>, W: AsyncWrite<E>>(
        &self,
        writer: &mut W,
    ) -> core::result::Result<usize, E> {
        let header_bytes_sent = self.header.send_async(writer).await?;

        #[cfg(not(feature = "alloc"))]
        let mut buf = [0u8; crate::consts::PAYLOAD_MAX_SIZE + SIGNATURE_LENGTH];
        #[cfg(feature = "alloc")]
        let mut buf = alloc::vec![0u8; self.body_length()];
        let body_bytes = &mut buf[..self.body_length()];

        self.fill_body_buffer(body_bytes);
        writer.write_all(body_bytes).await?;

        Ok(header_bytes_sent + self.body_length())
    }

    fn fill_body_buffer(&self, buf: &mut [u8]) {
        let payload_length = self.payload_length() as usize;

        let payload_bytes = self.payload.bytes();
        let bytes_to_copy = core::cmp::min(buf.len(), payload_bytes.len());
        buf[0..bytes_to_copy].copy_from_slice(&payload_bytes[0..bytes_to_copy]);

        let checksum_bytes: [u8; 2] = self.checksum.to_le_bytes();
        buf[payload_length..payload_length + 2].copy_from_slice(&checksum_bytes);

        if let Some(signature) = self.signature {
            let signature_bytes: SignatureBytes = signature.to_byte_array();
            let sig_start_idx = payload_length + 2;
            buf[sig_start_idx..self.body_length()].copy_from_slice(&signature_bytes);
        }
    }

    #[inline]
    fn from_raw_body(header: Header<V>, body_bytes: &[u8]) -> Frame<V> {
        let payload_bytes = &body_bytes[0..header.payload_length() as usize];
        let payload = Payload::new(header.message_id(), payload_bytes, header.version());

        let checksum_start = header.payload_length() as usize;
        let checksum_bytes = [body_bytes[checksum_start], body_bytes[checksum_start + 1]];
        let checksum: Checksum = Checksum::from_le_bytes(checksum_bytes);

        let signature: Option<Signature> = if header.is_signed() {
            let signature_start = checksum_start + CHECKSUM_SIZE;
            let signature_bytes = &body_bytes[signature_start..signature_start + SIGNATURE_LENGTH];
            Some(Signature::from_slice(signature_bytes))
        } else {
            None
        };

        Frame {
            header,
            payload,
            checksum,
            signature,
        }
    }
}

///////////////////////////////////////////////////////////////////////////////
//                                   V1/V2                                   //
///////////////////////////////////////////////////////////////////////////////
impl<V: Versioned> Frame<V> {
    /// Create [`FrameBuilder`] populated with current frame data.
    ///
    /// It is not possible to simply change a particular frame field since MAVLink frame data is
    /// tightly packed together, covered by CRC, and, in the case of `MAVLink 2` protocol, is
    /// potentially signed. Moreover, to alter a frame correctly we need a [`CrcExtra`] byte which
    /// is a part of a dialect, not the frame itself.
    ///
    /// This method provides a limited capability to alter frame data by creating a [`FrameBuilder`]
    /// populated with data of the current frame. For `MAVLink 2` frames this will drop frame's
    /// [`signature`](Frame::signature) and [`IncompatFlags::MAVLINK_IFLAG_SIGNED`] in
    /// [`incompat_flags`](Frame::incompat_flags) rendering frame unsigned. This process also
    /// requires from caller to provide a [`CrcExtra`] value to encoded message since
    /// [`checksum`](Frame::checksum) will be dropped as well and the information required to its
    /// this recalculation is not stored within MAVLink frame itself.
    ///
    /// It is not possible to rebuild [`Versionless`] frames since `MAVLink 2` [`Payload`] may
    /// contain extension fields and its trailing zero bytes are truncated which means it is not
    /// possible to reconstruct `MAVLink 1` [`payload_length`](Frame::payload_length) when
    /// downgrading frame protocol version.
    pub fn to_builder(
        &self,
    ) -> FrameBuilder<
        V,
        HasPayloadLen,
        Sequenced,
        HasSysId,
        HasCompId,
        HasMsgId,
        HasPayload,
        Unset,
        Unset,
    > {
        FrameBuilder {
            header_builder: self.header.to_builder(),
            payload: HasPayload(self.payload.clone()),
            crc_extra: Unset,
            signature: Unset,
        }
    }
}

///////////////////////////////////////////////////////////////////////////////
//                                    V2                                     //
///////////////////////////////////////////////////////////////////////////////
impl Frame<V2> {
    /// Incompatibility flags for `MAVLink 2` header.
    ///
    /// Flags that must be understood for MAVLink compatibility (implementation discards packet if
    /// it does not understand flag).
    ///
    /// See: [MAVLink 2 incompatibility flags](https://mavlink.io/en/guide/serialization.html#incompat_flags).
    #[inline]
    pub fn incompat_flags(&self) -> IncompatFlags {
        self.header.incompat_flags()
    }

    /// Compatibility flags for `MAVLink 2` header.
    ///
    /// Flags that can be ignored if not understood (implementation can still handle packet even if
    /// it does not understand flag).
    ///
    /// See: [MAVLink 2 compatibility flags](https://mavlink.io/en/guide/serialization.html#compat_flags).
    #[inline]
    pub fn compat_flags(&self) -> CompatFlags {
        self.header.compat_flags()
    }

    /// `MAVLink 2` signature `link_id`, an 8-bit identifier of a MAVLink channel.
    ///
    /// Peers may have different semantics or rules for different links. For example, some links may have higher
    /// priority over another during routing. Or even different secret keys for authorization.
    ///
    /// Available only for signed `MAVLink 2` frame. For `MAVLink 1` always return `None`.
    ///
    /// # Links
    ///
    /// * [`Self::signature`] from which [`Signature`] can be obtained. The former contains all signature-related fields
    ///   (if applicable).
    /// * [MAVLink 2 message signing](https://mavlink.io/en/guide/message_signing.html).
    pub fn link_id(&self) -> Option<SignedLinkId> {
        self.signature.map(|sig| sig.link_id)
    }

    /// `MAVLink 2` signature [`MavTimestamp`], a 48-bit value that specifies the moment when message was sent.
    ///
    /// The unit of measurement is the number of millisecond * 10 since MAVLink epoch (1st January 2015 GMT).
    ///
    /// According to MAVLink protocol, the sender must guarantee that the next timestamp is greater than the previous
    /// one.
    ///
    /// Available only for signed `MAVLink 2` frame. For `MAVLink 1` always return `None`.
    ///
    /// # Links
    ///
    /// * [`Self::signature`] from which [`Signature`] can be obtained. The former contains all signature-related fields
    ///   (if applicable).
    /// * [`MavTimestamp`] type which has utility function for converting from and into Unix timestamp.
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    pub fn timestamp(&self) -> Option<MavTimestamp> {
        self.signature.map(|sig| sig.timestamp)
    }

    /// Adds signature to `MAVLink 2` frame.
    ///
    /// Signs `MAVLink 2` frame with provided instance of `signer` that implements [`Sign`] trait and signature
    /// configuration specified as [`SigningConf`].
    ///
    /// # Links
    ///
    /// * [`Sign`] trait.
    /// * [`Signature`] struct which contains frame signature.
    /// * [MAVLink 2 message signing](https://mavlink.io/en/guide/message_signing.html).
    pub fn add_signature(&mut self, signer: &mut dyn Sign, conf: &SigningConf) -> &mut Self {
        conf.apply(self, signer);
        self
    }

    /// Validates frame signature using a `signer` and a secret `key`.
    ///
    /// Returns [`SignatureError`] if frame missing a signature or have an incorrect one.
    pub fn validate_signature(
        &self,
        signer: &mut dyn Sign,
        key: &SecretKey,
    ) -> core::result::Result<(), SignatureError> {
        let signature = if let Some(signature) = self.signature {
            signature
        } else {
            return Err(SignatureError);
        };
        let mut signer = Signer::new(signer);

        if !signer.validate(&self, &signature, key) {
            return Err(SignatureError);
        }

        Ok(())
    }
}

#[cfg(feature = "unsafe")]
impl<V: MaybeVersioned> TryUpdateFrom<&dyn Message> for Frame<V> {
    type Error = SpecError;

    /// <sup>`âš `</sup>
    /// Updates a frame with the data from the provided message.
    ///
    /// Replaces the following fields, that are guaranteed to be correct:
    ///
    /// * [`Frame::message_id`]
    /// * [`Frame::payload_length`]
    /// * [`Frame::payload`]
    /// * [`Frame::checksum`]
    ///
    /// **âš ** This method will strip [`Frame::signature`]. Make sure, that you know, how to sign
    /// the updated frame afterward.
    fn try_update_from(&mut self, value: &dyn Message) -> core::result::Result<(), Self::Error> {
        self.check_try_update_from(&value)?;
        unsafe { self.update_from_unchecked(value) }
        Ok(())
    }

    fn check_try_update_from(&self, value: &&dyn Message) -> core::result::Result<(), Self::Error> {
        value.encode(self.version())?;
        Ok(())
    }

    unsafe fn update_from_unchecked(&mut self, value: &dyn Message) {
        let payload = value.encode(self.version()).unwrap();
        let crc_extra = value.crc_extra();

        self.header.message_id = payload.id();
        self.header.payload_length = payload.length();
        self.payload = payload;
        self.checksum = self.calculate_crc(crc_extra);

        self.remove_signature();
    }
}

///////////////////////////////////////////////////////////////////////////////
//                                  TESTS                                    //
///////////////////////////////////////////////////////////////////////////////
#[cfg(test)]
mod tests {
    use super::*;

    #[cfg(feature = "std")]
    use std::io::Cursor;

    #[cfg(feature = "std")]
    use crate::io::{StdIoReader, StdIoWriter};

    #[test]
    fn crc_calculation_algorithm_accepts_sequential_digests() {
        // We just want to test that CRC algorithm is invariant in respect to the way we feed it
        // data.

        let data = [124, 12, 22, 34, 2, 148, 82, 201, 72, 0, 18, 215, 37, 63u8];
        let split_at: usize = data.len() / 2;

        // Get all data as one slice
        let mut crc_calculator_bulk = CRCu16::crc16mcrf4cc();
        crc_calculator_bulk.digest(&data);

        // Get data as two chunks sequentially
        let mut crc_calculator_seq = CRCu16::crc16mcrf4cc();
        crc_calculator_seq.digest(&data[0..split_at]);
        crc_calculator_seq.digest(&data[split_at..data.len()]);

        assert_eq!(crc_calculator_bulk.get_crc(), crc_calculator_seq.get_crc());
    }

    #[test]
    #[cfg(feature = "std")]
    fn multiple_magic_bytes_in_stream_v1() {
        use crate::consts::STX_V1;
        let seq = STX_V1;
        let reader = Cursor::new(vec![
            STX_V1, // magic byte
            8,      // payload_length
            seq,    // sequence
            10,     // system ID
            255,    // component ID
            0,      // message ID
            // -------------------------------
            1, 1, 1, 1, 1, 1, 1, 1, // Payload
            // -------------------------------
            0, 0, // Checksum (fake)
        ]);

        let mut receiver = crate::Receiver::new::<V1>(StdIoReader::new(reader));
        let frame = receiver.recv().unwrap();

        assert_eq!(frame.payload_length(), 8);
        assert_eq!(frame.sequence(), seq);
        assert_eq!(frame.system_id(), 10);
        assert_eq!(frame.component_id(), 255);
    }

    #[test]
    #[cfg(feature = "std")]
    fn multiple_magic_bytes_in_stream_v2() {
        use crate::consts::STX_V2;
        let seq = STX_V2;
        let reader = Cursor::new(vec![
            STX_V2, // magic byte
            8,      // payload_length
            0,      // incompatibility flags
            0,      // compatibility flags
            seq,    // sequence
            10,     // system ID
            255,    // component ID
            0,      // \
            0,      //  | message ID
            0,      // /
            // -------------------------------
            1, 1, 1, 1, 1, 1, 1, 1, // Payload
            // -------------------------------
            0, 0, // Checksum (fake)
        ]);

        let mut receiver = crate::Receiver::new::<V2>(StdIoReader::new(reader));
        let frame = receiver.recv().unwrap();

        assert_eq!(frame.payload_length(), 8);
        assert_eq!(frame.sequence(), seq);
        assert_eq!(frame.system_id(), 10);
        assert_eq!(frame.component_id(), 255);
    }

    #[test]
    #[cfg(feature = "std")]
    fn test_oversized_v2_payload() {
        use crate::consts::STX_V2;
        use crate::protocol::{Frame, Versionless};

        let payload_length = 3;
        let junk_bytes = 3;
        let in_buffer = vec![
            12,             // \
            24,             //  |Junk bytes
            240,            // /
            STX_V2,         // magic byte
            payload_length, // payload_length (INVALID since it should be 1)
            0,              // incompatibility flags
            0,              // compatibility flags
            1,              // sequence
            10,             // system ID
            255,            // component ID
            74,             // \
            0,              //  | message ID
            0,              // /
            0,              // \            (first byte is always present)
            0,              //  | payload   (INVALID) \
            0,              // /            (INVALID) / should not be present
            25,             // \
            25,             // / checksum
        ];
        let expected_frame_size = in_buffer.len() - 3; // no junk
        let valid_bytes = in_buffer[junk_bytes..].to_vec();
        let mut reader = StdIoReader::new(Cursor::new(in_buffer));

        // Read frame
        let frame = Frame::<Versionless>::recv(&mut reader).unwrap();

        // We should preserve payload length for compatibility
        assert_eq!(frame.payload_length(), payload_length);
        // Still, payload length should be one
        assert_eq!(frame.payload.bytes().len(), 1);

        // Send frame
        let mut out_buffer = StdIoWriter::new(Cursor::new(vec![]));
        let bytes_sent = frame.send(&mut out_buffer).unwrap();

        assert_eq!(bytes_sent, expected_frame_size);

        // Check that we send exactly what we received
        let mut out_bytes = vec![0u8; expected_frame_size];
        let mut out_buffer = out_buffer.extract();
        out_buffer.set_position(0);
        std::io::Read::read_exact(&mut out_buffer, out_bytes.as_mut_slice()).unwrap();
        assert_eq!(out_bytes, valid_bytes);
    }

    #[cfg(feature = "dlct-minimal")]
    mod dialect_utils {
        pub(super) use crate::dialects::minimal as dialect;
        pub(super) use crate::dialects::minimal::enums::{
            MavAutopilot, MavModeFlag, MavState, MavType,
        };
        pub(super) use crate::protocol::V1;
        pub(super) use dialect::messages::Heartbeat;

        pub(super) use super::super::*;

        pub(super) fn default_incompat_flags() -> IncompatFlags {
            IncompatFlags::BIT_3 | IncompatFlags::BIT_4
        }

        pub(super) fn default_compat_flags() -> CompatFlags {
            CompatFlags::BIT_5 | CompatFlags::BIT_6
        }

        pub(super) fn default_heartbeat_message() -> Heartbeat {
            Heartbeat {
                type_: MavType::FixedWing,
                autopilot: MavAutopilot::Generic,
                base_mode: MavModeFlag::TEST_ENABLED & MavModeFlag::CUSTOM_MODE_ENABLED,
                custom_mode: 0,
                system_status: MavState::Active,
                mavlink_version: dialect::Minimal::version().unwrap_or(0),
            }
        }

        #[cfg(feature = "std")]
        pub(super) fn all_zero_heartbeat_message() -> Heartbeat {
            Heartbeat {
                type_: MavType::Generic,          // 0
                autopilot: MavAutopilot::Generic, // 0
                base_mode: MavModeFlag::empty(),  // 0
                custom_mode: 0,
                system_status: MavState::Uninit, // 0
                mavlink_version: 0,
            }
        }

        pub(super) fn v1_frame(message: &dyn Message) -> Frame<V1> {
            Frame::builder()
                .sequence(7)
                .system_id(22)
                .component_id(17)
                .version(V1)
                .message(message)
                .unwrap()
                .build()
        }

        pub(super) fn v2_frame(message: &dyn Message) -> Frame<V2> {
            Frame::builder()
                .sequence(7)
                .system_id(22)
                .component_id(17)
                .version(V2)
                .incompat_flags(default_incompat_flags())
                .compat_flags(default_compat_flags())
                .message(message)
                .unwrap()
                .build()
        }

        pub(super) fn default_v1_heartbeat_frame() -> Frame<V1> {
            let message = default_heartbeat_message();
            v1_frame(&message)
        }

        pub(super) fn default_v2_heartbeat_frame() -> Frame<V2> {
            let message = default_heartbeat_message();
            v2_frame(&message)
        }
    }

    #[cfg(feature = "dlct-minimal")]
    use dialect_utils::*;

    #[test]
    #[cfg(feature = "dlct-minimal")]
    #[cfg(feature = "std")]
    fn test_v2_payload_truncation() {
        let message = all_zero_heartbeat_message();
        let frame = v2_frame(&message);

        assert_eq!(frame.payload_length(), 1);
        assert_eq!(frame.payload.bytes().len(), 1);
        assert_eq!(frame.payload.bytes(), &[0]);
    }

    #[test]
    #[cfg(feature = "dlct-minimal")]
    #[cfg(feature = "std")]
    fn test_signing() {
        use crate::consts::SIGNATURE_SECRET_KEY_LENGTH;
        use crate::utils::MavSha256;

        let mut frame = default_v2_heartbeat_frame();
        let frame = frame.add_signature(
            &mut MavSha256::default(),
            &SigningConf {
                link_id: 0,
                timestamp: Default::default(),
                secret: [0u8; SIGNATURE_SECRET_KEY_LENGTH].into(),
            },
        );

        assert!(frame.is_signed());
    }

    #[test]
    #[cfg(feature = "dlct-minimal")]
    fn test_decoding_to_message() {
        let _: dialect::Minimal = default_v2_heartbeat_frame().decode().unwrap();
    }

    #[test]
    #[cfg(feature = "dlct-minimal")]
    #[cfg(feature = "std")]
    fn test_rebuild_frame() {
        use crate::consts::SIGNATURE_SECRET_KEY_LENGTH;
        use crate::utils::MavSha256;

        let mut frame = default_v2_heartbeat_frame();
        frame.add_signature(
            &mut MavSha256::default(),
            &SigningConf {
                link_id: 0,
                timestamp: Default::default(),
                secret: [0u8; SIGNATURE_SECRET_KEY_LENGTH].into(),
            },
        );

        let updated = frame
            .to_builder()
            .crc_extra(dialect::messages::heartbeat::spec().crc_extra())
            .build();

        assert_eq!(updated.sequence(), frame.sequence());
        assert_eq!(updated.system_id(), frame.system_id());
        assert_eq!(updated.component_id(), frame.component_id());
        assert_eq!(updated.payload_length(), frame.payload_length());
        assert_eq!(updated.payload().bytes(), frame.payload().bytes());
        assert_eq!(updated.checksum(), frame.checksum());

        assert_eq!(
            updated.incompat_flags().bits(),
            default_incompat_flags().bits()
        );
        assert_eq!(updated.compat_flags().bits(), default_compat_flags().bits());
        assert!(!updated.is_signed());
    }

    #[test]
    #[cfg(feature = "dlct-minimal")]
    fn test_upgrade_frame() {
        let expected = default_v2_heartbeat_frame();

        let upgraded = default_v1_heartbeat_frame()
            .to_builder()
            .crc_extra(dialect::messages::heartbeat::spec().crc_extra())
            .upgrade()
            .incompat_flags(default_incompat_flags())
            .compat_flags(default_compat_flags())
            .build();

        assert_eq!(upgraded.payload_length(), expected.payload_length());
        assert_eq!(upgraded.payload().bytes(), expected.payload().bytes());
        assert_eq!(upgraded.checksum(), expected.checksum());
    }

    #[test]
    #[cfg(feature = "dlct-minimal")]
    fn test_try_versioned() {
        let v1 = default_v1_heartbeat_frame();
        assert!(v1.clone().try_into_versioned::<V1>().is_ok());
        assert!(v1.clone().try_into_versioned::<V2>().is_err());
        assert!(v1.clone().try_into_versioned::<Versionless>().is_ok());

        let versionless_v1 = v1.into_versionless();
        assert!(versionless_v1.clone().try_into_versioned::<V1>().is_ok());
        assert!(versionless_v1.clone().try_into_versioned::<V2>().is_err());
        assert!(versionless_v1
            .clone()
            .try_into_versioned::<Versionless>()
            .is_ok());

        let v2 = default_v2_heartbeat_frame();
        assert!(v2.clone().try_into_versioned::<V1>().is_err());
        assert!(v2.clone().try_into_versioned::<V2>().is_ok());
        assert!(v2.clone().try_into_versioned::<Versionless>().is_ok());

        let versionless_v2 = v2.into_versionless();
        assert!(versionless_v2.clone().try_into_versioned::<V1>().is_err());
        assert!(versionless_v2.clone().try_into_versioned::<V2>().is_ok());
        assert!(versionless_v2
            .clone()
            .try_into_versioned::<Versionless>()
            .is_ok());
    }

    #[test]
    fn serialize_deserialize_v1_frame() {
        use crate::consts::STX_V1;
        const FRAME_LENGTH: usize = 16;

        let sequence = [
            21,     // \
            21,     //  | Junk bytes
            21,     // /
            STX_V1, // magic byte
            8,      // payload_length
            42,     // sequence
            10,     // system ID
            255,    // component ID
            31,     // message ID
            // -------------------------------
            1, 2, 3, 4, 5, 6, 7, 8, // Payload
            // -------------------------------
            0, 0,  // Checksum (fake)
            41, // \
            41, //  | Junk bytes
            41, // /
        ];
        let frame_bytes = &sequence[3..FRAME_LENGTH + 3];
        let frame_with_extra_bytes = &sequence[3..];

        // Deserialize from exact sequence
        let frame = unsafe { Frame::<V1>::deserialize(frame_bytes) }.unwrap();
        assert_eq!(frame.payload_length(), 8);
        assert_eq!(frame.sequence(), 42);
        assert_eq!(frame.system_id(), 10);
        assert_eq!(frame.component_id(), 255);
        assert_eq!(frame.message_id(), 31);
        assert_eq!(frame.payload.bytes(), &[1, 2, 3, 4, 5, 6, 7, 8]);
        assert_eq!(frame.checksum(), 0);

        // Serialize
        let mut serialized: [u8; FRAME_LENGTH] = [0; FRAME_LENGTH];
        frame.serialize(&mut serialized).unwrap();
        assert_eq!(serialized, frame_bytes);

        // Deserialize from a sequence with extra bytes
        let frame = unsafe { Frame::<V1>::deserialize(frame_with_extra_bytes) }.unwrap();
        let mut serialized: [u8; FRAME_LENGTH] = [0; FRAME_LENGTH];
        frame.serialize(&mut serialized).unwrap();
        assert_eq!(serialized, frame_bytes);

        // Deserialize from an incorrect start
        assert!(matches!(
            unsafe { Frame::<V1>::deserialize(&sequence) },
            Err(FrameError::InvalidHeader)
        ));
    }

    #[test]
    fn serialize_deserialize_v2_frame() {
        use crate::consts::STX_V2;
        const FRAME_LENGTH: usize = 33;

        let sequence = [
            21,     // \
            21,     //  | Junk bytes
            21,     // /
            STX_V2, // magic byte
            8,      // payload_length
            1,      // incompatibility flags
            0,      // compatibility flags
            42,     // sequence
            10,     // system ID
            255,    // component ID
            2,      // \
            1,      //  | message ID
            0,      // /
            // -------------------------------
            1, 2, 3, 4, 5, 6, 7, 8, // Payload
            // -------------------------------
            0, 0, // Checksum (fake)
            // -------------------------------
            1, 2, 3, 4, 5, 6, 7, 8, 9, 0, 1, 2, 3, // Signature (fake)
            // -------------------------------
            41, // \
            41, //  | Junk bytes
            41, // /
        ];
        let frame_bytes = &sequence[3..FRAME_LENGTH + 3];
        let frame_with_extra_bytes = &sequence[3..];

        // Deserialize from exact sequence
        let frame = unsafe { Frame::<V2>::deserialize(frame_bytes) }.unwrap();
        assert_eq!(frame.payload_length(), 8);
        assert_eq!(frame.sequence(), 42);
        assert_eq!(frame.system_id(), 10);
        assert_eq!(frame.component_id(), 255);
        assert_eq!(frame.message_id(), 258);
        assert_eq!(frame.payload.bytes(), &[1, 2, 3, 4, 5, 6, 7, 8]);
        assert_eq!(frame.checksum(), 0);
        assert_eq!(
            frame.signature().unwrap().to_byte_array().as_slice(),
            &[1, 2, 3, 4, 5, 6, 7, 8, 9, 0, 1, 2, 3]
        );

        // Serialize
        let mut serialized: [u8; FRAME_LENGTH] = [0; FRAME_LENGTH];
        frame.serialize(&mut serialized).unwrap();
        assert_eq!(serialized, frame_bytes);

        // Deserialize from a sequence with extra bytes
        let frame = unsafe { Frame::<V2>::deserialize(frame_with_extra_bytes) }.unwrap();
        let mut serialized: [u8; FRAME_LENGTH] = [0; FRAME_LENGTH];
        frame.serialize(&mut serialized).unwrap();
        assert_eq!(serialized, frame_bytes);

        // Deserialize from an incorrect start
        assert!(matches!(
            unsafe { Frame::<V1>::deserialize(&sequence) },
            Err(FrameError::InvalidHeader)
        ));
    }
}