mavlink_core/
utils.rs

1//! Utilities for processing MAVLink messages
2
3/// Removes the trailing zeroes in the payload
4///
5/// # Note:
6///
7/// There must always be at least one remaining byte even if it is a
8/// zero byte.
9pub fn remove_trailing_zeroes(data: &[u8]) -> usize {
10    let mut len = data.len();
11
12    while len > 1 && data[len - 1] == 0 {
13        len -= 1;
14    }
15
16    len
17}
18
19/// A trait very similar to [`Default`] but is only implemented for the equivalent Rust types to
20/// `MavType`s.
21///
22/// This is only needed because rust doesn't currently implement `Default` for arrays
23/// of all sizes. In particular this trait is only ever used when the "serde" feature is enabled.
24/// For more information, check out [this issue](https://users.rust-lang.org/t/issue-for-derives-for-arrays-greater-than-size-32/59055/3).
25pub trait RustDefault: Copy {
26    fn rust_default() -> Self;
27}
28
29impl<T: RustDefault, const N: usize> RustDefault for [T; N] {
30    #[inline(always)]
31    fn rust_default() -> Self {
32        let val: T = RustDefault::rust_default();
33        [val; N]
34    }
35}
36
37macro_rules! impl_rust_default {
38    ($($t:ty => $val:expr),* $(,)?) => {
39        $(impl RustDefault for $t {
40            #[inline(always)]
41            fn rust_default() -> Self { $val }
42        })*
43    };
44}
45
46impl_rust_default! {
47    u8 => 0,
48    i8 => 0,
49    u16 => 0,
50    i16 => 0,
51    u32 => 0,
52    i32 => 0,
53    u64 => 0,
54    i64 => 0,
55    f32 => 0.0,
56    f64 => 0.0,
57    char => '\0',
58}
59
60#[cfg(test)]
61mod tests {
62    use super::*;
63
64    #[test]
65    fn test_remove_trailing_zeroes_empty_slice() {
66        remove_trailing_zeroes(&[]);
67    }
68}
69
70#[cfg(feature = "serde")]
71pub mod nulstr {
72    use serde::de::Deserializer;
73    use serde::ser::Serializer;
74    use serde::Deserialize;
75    use std::str;
76
77    pub fn serialize<S, const N: usize>(value: &[u8; N], serializer: S) -> Result<S::Ok, S::Error>
78    where
79        S: Serializer,
80    {
81        let nul_pos = value.iter().position(|&b| b == 0).unwrap_or(N);
82        let s = str::from_utf8(&value[..nul_pos]).map_err(serde::ser::Error::custom)?;
83        serializer.serialize_str(s)
84    }
85
86    pub fn deserialize<'de, D, const N: usize>(deserializer: D) -> Result<[u8; N], D::Error>
87    where
88        D: Deserializer<'de>,
89    {
90        let s: String = Deserialize::deserialize(deserializer)?;
91        let mut buf = [0u8; N];
92        let bytes = s.as_bytes();
93        let len = bytes.len().min(N);
94        buf[..len].copy_from_slice(&bytes[..len]);
95        Ok(buf)
96    }
97}