uf_crsf/packets/
vario.rs

1use crate::packets::CrsfPacket;
2use crate::packets::PacketType;
3use crate::CrsfParsingError;
4
5/// Represents a Variometer Sensor packet.
6#[derive(Clone, Debug, PartialEq)]
7#[cfg_attr(feature = "defmt", derive(defmt::Format))]
8pub struct VariometerSensor {
9    /// Vertical speed in cm/s.
10    pub v_speed: i16,
11}
12
13impl VariometerSensor {
14    pub fn new(v_speed: i16) -> Result<Self, CrsfParsingError> {
15        Ok(Self { v_speed })
16    }
17}
18
19impl CrsfPacket for VariometerSensor {
20    const PACKET_TYPE: PacketType = PacketType::Vario;
21    const MIN_PAYLOAD_SIZE: usize = 2;
22
23    fn to_bytes(&self, buffer: &mut [u8]) -> Result<usize, CrsfParsingError> {
24        self.validate_buffer_size(buffer)?;
25        buffer[..2].copy_from_slice(&self.v_speed.to_be_bytes());
26        Ok(Self::MIN_PAYLOAD_SIZE)
27    }
28
29    fn from_bytes(data: &[u8]) -> Result<Self, CrsfParsingError> {
30        if data.len() != Self::MIN_PAYLOAD_SIZE {
31            return Err(CrsfParsingError::InvalidPayloadLength);
32        }
33
34        Ok(Self {
35            v_speed: i16::from_be_bytes([data[0], data[1]]),
36        })
37    }
38}
39
40#[cfg(test)]
41mod tests {
42    use super::*;
43
44    #[test]
45    fn test_vario_from_bytes() {
46        assert_eq!(VariometerSensor::MIN_PAYLOAD_SIZE, 2);
47        let data: [u8; 2] = [0x01, 0x02];
48        let packet = VariometerSensor::from_bytes(&data).unwrap();
49        assert_eq!(packet.v_speed, 0x0102);
50    }
51
52    #[test]
53    fn test_vario_to_bytes() {
54        let packet = VariometerSensor { v_speed: -1000 };
55        let mut buffer = [0u8; 2];
56        let len = packet.to_bytes(&mut buffer).unwrap();
57        assert_eq!(len, 2);
58        let expected: [u8; 2] = [0xFC, 0x18];
59        assert_eq!(buffer, expected);
60    }
61
62    #[test]
63    fn test_vario_round_trip() {
64        let packet = VariometerSensor { v_speed: 1234 };
65        let mut buffer = [0u8; 2];
66        packet.to_bytes(&mut buffer).unwrap();
67        let round_trip = VariometerSensor::from_bytes(&buffer).unwrap();
68        assert_eq!(packet, round_trip);
69    }
70
71    #[test]
72    fn test_vario_from_bytes_too_small() {
73        let data: [u8; 1] = [0; 1];
74        let result = VariometerSensor::from_bytes(&data);
75        assert_eq!(result, Err(CrsfParsingError::InvalidPayloadLength));
76    }
77
78    #[test]
79    fn test_vario_to_bytes_too_small() {
80        let packet = VariometerSensor { v_speed: 1 };
81        let mut buffer = [0u8; 1];
82        let result = packet.to_bytes(&mut buffer);
83        assert_eq!(result, Err(CrsfParsingError::BufferOverflow));
84    }
85}