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
use core::cmp::min;
use core::fmt::{Debug, Formatter};

#[cfg(feature = "std")]
use std::time::{SystemTime, UNIX_EPOCH};

use crate::consts::{
    SIGNATURE_LENGTH, SIGNATURE_LINK_ID_LENGTH, SIGNATURE_SECRET_KEY_LENGTH,
    SIGNATURE_TIMESTAMP_LENGTH, SIGNATURE_TIMESTAMP_OFFSET, SIGNATURE_VALUE_LENGTH,
};
use crate::protocol::{
    Frame, MaybeVersioned, SignatureBytes, SignatureTimestampBytes, SignatureValue, SignedLinkId,
    V2,
};

/// `MAVLink 2` packet signature.
///
/// # Links
///
/// * [MAVLink 2 message signing](https://mavlink.io/en/guide/message_signing.html).
#[derive(Clone, Copy, Debug)]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct Signature {
    /// `ID` of link on which packet is sent.
    pub link_id: SignedLinkId,
    /// Timestamp in 10 microsecond units since the beginning of MAVLink epoch (1st January 2015 GMT).
    pub timestamp: MavTimestamp,
    /// Value of a signature.
    pub value: SignatureValue,
}

/// A 48-bit timestamp used for `MAVLink 2` packet signing.
///
/// MAVLink signature timestamp is a 48-bit value that equals to the number of milliseconds * 10
/// since the start of the MAVLink epoch (1st January 2015 GMT).
///
/// # Links
///
/// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
/// * [`Signature`] is a section of MAVLink packet where timestamp is stored.
#[derive(Clone, Copy, Debug, Default)]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct MavTimestamp {
    raw: u64,
}

/// Interface for `MAVLink 2` frames signing algorithm.
///
/// An implementor of [`Sign`] should be capable to calculate `sha256_48`, a `MAVLink 2` specific
/// hashing algorithm similar to regular `sha256` except that only first 48 bits are considered.
///
/// # Links
///
/// * [`Signer`] wraps and implementor of [`Sign`] and capable of signing and validating frames.
/// * Values calculated by implementors of [`Sign`] are stored in [`Signature`] struct as `value`.
/// * [Signature specification](https://mavlink.io/en/guide/message_signing.html#signature) format in MAVLink docs.
pub trait Sign {
    /// Reset inner state of a signer.
    ///
    /// Used by caller to ensure that signer's inner state does not have any digested data.
    fn reset(&mut self);

    /// Adds value to digest.
    ///
    /// Caller can invoke [`Sign::digest`] multiple times. Passing data as several sequential chunks
    /// is the same as calling `digest` with the whole data at once.
    fn digest(&mut self, bytes: &[u8]);

    /// Produces `MAVLink 2` signature from the internal state.
    fn produce(&self) -> SignatureValue;
}

/// Frame signer.
///
/// Stores an implementor of [`Sign`] and provides methods for signing frames and validating their
/// signatures.
pub struct Signer<'a>(&'a mut dyn Sign);

/// Message signing configuration for [`Frame`].
///
/// **⚠** Secret key is excluded from [Serde](https://serde.rs) serialization.
///
/// # Links
///
/// * [`Sign`] trait defines signing algorithm protocol.
/// * [Signature specification](https://mavlink.io/en/guide/message_signing.html#signature) in MAVLink docs.
#[derive(Clone, Debug)]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct SigningConf {
    /// Defines [`Signature::link_id`] that will be appended to MAVLink packet upon signing.
    pub link_id: SignedLinkId,
    /// Defines [`Signature::timestamp`] that will be appended to MAVLink packet upon signing.
    pub timestamp: MavTimestamp,
    /// Secret key is used to calculate [`Signature::value`].
    ///
    /// **⚠** Since `secret` contains sensitive value, it will be excluded from
    /// [Serde](https://serde.rs) serialization.
    #[cfg_attr(feature = "serde", serde(skip_serializing))]
    pub secret: SecretKey,
}

impl<'a> Signer<'a> {
    /// Creates a [`Signer`] from anything that implements [`Sign`].
    pub fn new(signer: &'a mut dyn Sign) -> Self {
        Self(signer)
    }

    /// Calculates `MAVLink 2` signature for a [`Frame`] using provided `link_id`, `timestamp`, and
    /// `key`.
    ///
    /// This method has a blanked implementation which does not require changing, unless you want
    /// to completely change signing protocol.
    pub fn calculate<V: MaybeVersioned>(
        &mut self,
        frame: &Frame<V>,
        link_id: SignedLinkId,
        timestamp: MavTimestamp,
        key: &SecretKey,
    ) -> SignatureValue {
        self.0.reset();

        self.0.digest(key.value());
        self.0.digest(frame.header().decode().as_slice());
        self.0.digest(frame.payload().bytes());
        self.0.digest(&frame.checksum().to_le_bytes());
        self.0.digest(&[link_id]);
        self.0.digest(&timestamp.to_bytes_array());

        self.0.produce()
    }

    /// Validates a [`Signature`] using the provided [`SecretKey`]. Returns `true` if signature is
    /// valid.
    pub fn validate<V: MaybeVersioned>(
        &mut self,
        frame: &Frame<V>,
        signature: &Signature,
        key: &SecretKey,
    ) -> bool {
        let expected_value = self.calculate(&frame, signature.link_id, signature.timestamp, key);

        expected_value == signature.value
    }
}

impl SigningConf {
    /// Signs a [`Frame`] using stored signing configuration and provided `signer`.
    ///
    /// This method signs `MAVLink 2` frames keeping `MAVLink 1` frames unchanged.
    pub fn apply<V: MaybeVersioned>(&self, frame: &mut Frame<V>, signer: &mut dyn Sign) {
        if !frame.matches_version(V2) {
            return;
        }

        frame.header.set_is_signed(true);

        let mut signer = Signer::new(signer);
        let value = signer.calculate(frame, self.link_id, self.timestamp, &self.secret);

        frame.signature = Some(Signature {
            link_id: self.link_id,
            timestamp: self.timestamp,
            value,
        });
    }
}

/// `MAVLink 2` signature secret key.
///
/// A 32-byte secret key for `MAVLink 2` message signing.
///
/// Can be constructed from various inputs. If input is too small, then remaining bytes will be set
/// to zeros. If input is larger than [`SIGNATURE_SECRET_KEY_LENGTH`], then all trailing bytes will
/// be dropped.
///
/// # Usage
///
/// Construct a secret key from byte array.
///
/// ```rust
/// use mavio::protocol::SecretKey;
/// use mavio::consts::SIGNATURE_SECRET_KEY_LENGTH;
///
/// let key = SecretKey::from([0x1e; SIGNATURE_SECRET_KEY_LENGTH]);
/// ```
///
/// Construct a secret key from a smaller byte slice, setting remaining bytes with zeros. For
/// slices larger than [`SIGNATURE_SECRET_KEY_LENGTH`], all trailing bytes will be ignored.
///
/// ```rust
/// use mavio::protocol::SecretKey;
///
/// let key = SecretKey::from([0x1eu8; 10].as_slice());
/// ```
///
/// Construct a secret key from `&str` ([`String`] and `&String` are also supported).
///
/// ```rust
/// use mavio::protocol::SecretKey;
///
/// let key = SecretKey::from("password");
/// ```
///
/// # Links
///
///  * [`Signature`] is a container for storing `MAVLink 2` signature.
///  * [`Sign`] is a trait which `sha256_48` algorithms should implement.
///  * `signature` field in [MAVLink 2 message signing](https://mavlink.io/en/guide/message_signing.html).
#[derive(Clone, Default)]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct SecretKey([u8; SIGNATURE_SECRET_KEY_LENGTH]);

impl Debug for SecretKey {
    fn fmt(&self, f: &mut Formatter<'_>) -> core::fmt::Result {
        f.debug_struct("SecretKey").finish_non_exhaustive()
    }
}

impl From<[u8; SIGNATURE_SECRET_KEY_LENGTH]> for SecretKey {
    fn from(value: [u8; SIGNATURE_SECRET_KEY_LENGTH]) -> Self {
        Self(value)
    }
}

impl From<&[u8]> for SecretKey {
    fn from(value: &[u8]) -> Self {
        let len = min(value.len(), SIGNATURE_SECRET_KEY_LENGTH);
        let mut key = [0u8; SIGNATURE_SECRET_KEY_LENGTH];
        key[0..len].copy_from_slice(&value[0..len]);
        Self(key)
    }
}

impl From<&str> for SecretKey {
    fn from(value: &str) -> Self {
        value.as_bytes().into()
    }
}

#[cfg(feature = "alloc")]
impl From<String> for SecretKey {
    fn from(value: String) -> Self {
        value.as_str().into()
    }
}

#[cfg(feature = "alloc")]
impl From<&String> for SecretKey {
    fn from(value: &String) -> Self {
        value.as_str().into()
    }
}

impl SecretKey {
    /// Returns secret key value as slice.
    pub fn value(&self) -> &[u8] {
        self.0.as_slice()
    }
}

impl From<SignatureBytes> for Signature {
    #[inline]
    fn from(value: SignatureBytes) -> Self {
        Self::from_byte_array(value)
    }
}

impl From<Signature> for SignatureBytes {
    /// Encodes [`Signature`] into [`SignatureBytes`] byte array.
    ///
    /// #Links
    ///
    /// * [`Signature::to_byte_array`].
    #[inline]
    fn from(value: Signature) -> Self {
        value.to_byte_array()
    }
}

impl Default for SigningConf {
    /// Instantiates [`SigningConf`] with default values.
    ///
    /// Sets `secret` bytes to `0xff` which is recommended as a masked value by
    /// [MAVLink documentation](https://mavlink.io/en/guide/message_signing.html#logging).
    fn default() -> Self {
        Self {
            link_id: 0,
            timestamp: Default::default(),
            secret: [0xff; SIGNATURE_SECRET_KEY_LENGTH].into(),
        }
    }
}

impl Signature {
    /// Signature `link_id` is 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.
    #[inline(always)]
    pub fn link_id(&self) -> SignedLinkId {
        self.link_id
    }

    /// Signature [`MavTimestamp`] is 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.
    ///
    /// # Links
    ///
    /// * [`MavTimestamp`] struct.
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline]
    pub fn timestamp(&self) -> MavTimestamp {
        self.timestamp
    }

    /// Signature `value` is cryptographic 48-bit hash that depends on the entire frame content.
    ///
    /// # Links
    ///
    /// * [Signature specification](https://mavlink.io/en/guide/message_signing.html#signature) in MAVLink docs.
    #[inline]
    pub fn value(&self) -> SignatureValue {
        self.value
    }

    /// Decodes an array of bytes into [`Signature`].
    #[inline(always)]
    pub fn from_byte_array(bytes: SignatureBytes) -> Self {
        Self::from_slice(bytes.as_slice())
    }

    /// Encodes [`Signature`] into [`SignatureBytes`] byte array.
    ///
    /// Used in [`From<MavLinkV2Signature>`](From) trait implementation for [`SignatureBytes`].
    pub fn to_byte_array(&self) -> SignatureBytes {
        let mut bytes: SignatureBytes = Default::default();

        let timestamp_offset = SIGNATURE_LINK_ID_LENGTH;
        let signature_value_offset = SIGNATURE_LINK_ID_LENGTH + SIGNATURE_TIMESTAMP_LENGTH;

        bytes[0] = self.link_id;
        bytes[timestamp_offset..signature_value_offset]
            .copy_from_slice(&self.timestamp.to_bytes_array());
        bytes[signature_value_offset..SIGNATURE_LENGTH].copy_from_slice(&self.value);

        bytes
    }

    pub(crate) fn from_slice(bytes: &[u8]) -> Self {
        let link_id = bytes[0];
        let mut timestamp_bytes: SignatureTimestampBytes = Default::default();
        let mut signature: SignatureValue = Default::default();

        let timestamp_start = SIGNATURE_LINK_ID_LENGTH;
        let timestamp_end = timestamp_start + SIGNATURE_TIMESTAMP_LENGTH;
        timestamp_bytes.copy_from_slice(&bytes[timestamp_start..timestamp_end]);
        let timestamp: MavTimestamp = timestamp_bytes.into();

        let value_start = timestamp_end;
        let value_end = value_start + SIGNATURE_VALUE_LENGTH;
        signature.copy_from_slice(&bytes[timestamp_end..value_end]);

        Self {
            link_id,
            timestamp,
            value: signature,
        }
    }
}

#[cfg(feature = "std")]
impl From<SystemTime> for MavTimestamp {
    /// Creates [`MavTimestamp`] from the [`SystemTime`].
    ///
    /// Available only when `std` feature is enabled. Uses [`Self::from_system_time`] internally.
    #[inline(always)]
    fn from(value: SystemTime) -> Self {
        Self::from_system_time(value)
    }
}

impl From<u64> for MavTimestamp {
    /// Creates [`MavTimestamp`] from [`u64`] raw value discarding two higher bytes.
    ///
    /// Uses [Self::from_raw_u64] internally.
    #[inline(always)]
    fn from(value: u64) -> Self {
        Self::from_raw_u64(value)
    }
}

impl From<SignatureTimestampBytes> for MavTimestamp {
    /// Decodes [`MavTimestamp`] from bytes.
    ///
    /// Uses [`MavTimestamp::from_bytes`].
    #[inline(always)]
    fn from(bytes: SignatureTimestampBytes) -> Self {
        Self::from_bytes(&bytes)
    }
}

impl From<MavTimestamp> for SignatureTimestampBytes {
    /// Encodes [`MavTimestamp`] into bytes.
    ///
    /// Uses [`MavTimestamp::to_bytes_array`].
    #[inline(always)]
    fn from(timestamp: MavTimestamp) -> Self {
        timestamp.to_bytes_array()
    }
}

impl MavTimestamp {
    /// Creates [`MavTimestamp`] from milliseconds since the beginning of the Unix epoch.
    pub fn from_millis(value: u64) -> Self {
        let mut timestamp = MavTimestamp::default();
        timestamp.set_millis(value);
        timestamp
    }

    /// Creates [`MavTimestamp`] from microseconds since the beginning of the Unix epoch.
    pub fn from_micros(value: u128) -> Self {
        let mut timestamp = MavTimestamp::default();
        timestamp.set_micros(value);
        timestamp
    }

    /// Creates [`MavTimestamp`] from the [`SystemTime`]. Uses microsecond * 10 precision.
    ///
    /// Available only when `std` feature is enabled.
    #[cfg(feature = "std")]
    pub fn from_system_time(value: SystemTime) -> Self {
        Self::from_micros(value.duration_since(UNIX_EPOCH).unwrap().as_micros())
    }

    /// Creates [`MavTimestamp`] from [`u64`] raw value discarding two higher bytes.
    ///
    /// Provided `value` should represent [`Self::as_raw_u64`] `MAVLink 2` signature timestamp.
    pub fn from_raw_u64(value: u64) -> Self {
        // Discard two higher bytes.
        let raw = value & 0xffffffffffff;
        Self { raw }
    }

    /// Decodes timestamp from bytes.
    ///
    /// # Links
    ///
    /// * [`MavTimestamp`]
    /// * [`SignatureTimestampBytes`]
    /// * [`Signature`]
    pub fn from_bytes(bytes: &SignatureTimestampBytes) -> Self {
        let mut bytes_u64 = [0u8; 8];
        bytes_u64[0..SIGNATURE_TIMESTAMP_LENGTH].copy_from_slice(bytes);
        Self {
            raw: u64::from_le_bytes(bytes_u64),
        }
    }

    /// Raw MAVLink timestamp value.
    ///
    /// Returns number of milliseconds * 10 since the start of MAVLink epoch (1st January 2015 GMT).
    ///
    /// Use [`Self::as_raw_u64`] to set this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn as_raw_u64(&self) -> u64 {
        self.raw
    }

    /// Sets raw MAVLink timestamp value.
    ///
    /// Use [`Self::as_raw_u64`] to get this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn set_raw_u64(&mut self, raw: u64) -> &mut Self {
        self.raw = raw & 0xffffffffffff;
        self
    }

    /// MAVLink timestamp in milliseconds.
    ///
    /// Returns timestamp as a number of milliseconds since the start of MAVLink epoch
    /// (1st January 2015 GMT).
    ///
    /// Use [`Self::as_millis_mavlink`] to set this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn as_millis_mavlink(&self) -> u64 {
        self.raw / 100
    }

    /// Sets MAVLink timestamp in milliseconds.
    ///
    /// Use [`Self::as_millis_mavlink`] to get this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn set_millis_mavlink(&mut self, millis_mavlink: u64) -> &mut Self {
        self.raw = (millis_mavlink * 100) & 0xffffffffffff;
        self
    }

    /// Unix timestamp in milliseconds.
    ///
    /// Use [`Self::set_millis`] to set this value.
    ///
    /// Returns value as number of milliseconds since the start of Unix epoch (1st January 1970 GMT).
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    /// * [`SIGNATURE_TIMESTAMP_OFFSET`] defines offset between epochs.
    #[inline(always)]
    pub fn as_millis(&self) -> u64 {
        (self.raw + SIGNATURE_TIMESTAMP_OFFSET * 100_000) / 100
    }

    /// Sets Unix timestamp in milliseconds.
    ///
    /// Use [`Self::as_millis`] to get this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn set_millis(&mut self, millis: u64) -> &mut Self {
        self.set_millis_mavlink(millis - SIGNATURE_TIMESTAMP_OFFSET * 1000);
        self
    }

    /// MAVLink timestamp in microseconds.
    ///
    /// Returns timestamp as a number of microseconds since the start of MAVLink epoch
    /// (1st January 2015 GMT).
    ///
    /// Use [`Self::set_micros_mavlink`] to set this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn as_micros_mavlink(&self) -> u128 {
        self.raw as u128 * 10
    }

    /// Sets MAVLink timestamp in microseconds.
    ///
    /// Use [`Self::as_micros_mavlink`] to get this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn set_micros_mavlink(&mut self, micros_mavlink: u128) -> &mut Self {
        self.raw = (micros_mavlink / 10) as u64 & 0xffffffffffff;
        self
    }

    /// Unix timestamp in microseconds.
    ///
    /// Returns value as number of microseconds since the start of Unix epoch (1st January 1970 GMT).
    ///
    /// Use [`Self::set_micros`] to set this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    /// * [`SIGNATURE_TIMESTAMP_OFFSET`] defines offset between epochs.
    #[inline(always)]
    pub fn as_micros(&self) -> u128 {
        (self.raw as u128 + SIGNATURE_TIMESTAMP_OFFSET as u128 * 100_000) * 10
    }

    /// Sets Unix timestamp in microseconds.
    ///
    /// Use [`Self::as_micros`] to get this value.
    ///
    /// # Links
    ///
    /// * [Timestamp handling](https://mavlink.io/en/guide/message_signing.html#timestamp) in MAVLink documentation.
    #[inline(always)]
    pub fn set_micros(&mut self, micros: u128) -> &mut Self {
        self.set_micros_mavlink(micros - SIGNATURE_TIMESTAMP_OFFSET as u128 * 1_000_000);
        self
    }

    /// Encodes timestamp into bytes.
    ///
    /// # Links
    ///
    /// * [`MavTimestamp`]
    /// * [`SignatureTimestampBytes`]
    /// * [`Signature`]
    pub fn to_bytes_array(&self) -> SignatureTimestampBytes {
        let bytes_u64: [u8; 8] = self.raw.to_le_bytes();
        let mut bytes = [0u8; SIGNATURE_TIMESTAMP_LENGTH];
        bytes.copy_from_slice(&bytes_u64[0..SIGNATURE_TIMESTAMP_LENGTH]);
        bytes
    }
}

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

    #[test]
    fn key_from_array() {
        let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH]);
        assert_eq!(key.value(), [1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());
    }

    #[test]
    fn key_from_slice() {
        let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());
        assert_eq!(key.value(), [1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());

        let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH + 10].as_slice());
        assert_eq!(key.value(), [1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());

        let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH - 10].as_slice());
        let mut expected = [0u8; SIGNATURE_SECRET_KEY_LENGTH];
        expected[0..SIGNATURE_SECRET_KEY_LENGTH - 10]
            .copy_from_slice(&[1u8; SIGNATURE_SECRET_KEY_LENGTH - 10]);
        assert_eq!(key.value(), expected);
    }

    #[test]
    #[cfg(feature = "alloc")]
    fn key_from_strings() {
        let expected = {
            let mut expected = [0u8; SIGNATURE_SECRET_KEY_LENGTH];
            expected[0..6].copy_from_slice("abcdef".as_bytes());
            expected
        };

        let key_str = "abcdef".to_string();

        let key = SecretKey::from(key_str.as_str());
        assert_eq!(key.value(), expected);

        let key = SecretKey::from(&key_str);
        assert_eq!(key.value(), expected);

        let key = SecretKey::from(key_str);
        assert_eq!(key.value(), expected);
    }

    #[test]
    #[cfg(feature = "std")]
    fn timestamp_std_basics() {
        let now = SystemTime::now();
        let timestamp = MavTimestamp::from(now);

        assert_eq!(
            timestamp.as_millis(),
            now.duration_since(UNIX_EPOCH).unwrap().as_millis() as u64
        );

        assert_eq!(
            timestamp.as_micros(),
            now.duration_since(UNIX_EPOCH).unwrap().as_micros() / 10 * 10
        );
    }
}