Skip to main content

cu_msp_lib/
structs.rs

1//! MSP structures
2
3use packed_struct::derive::{PackedStruct, PrimitiveEnum};
4use serde::{Deserialize, Serialize};
5
6use crate::MspPacketDirection::{FromFlightController, ToFlightController};
7use crate::commands::MspCommandCode;
8use crate::{MSP_MAX_PAYLOAD_LEN, MspPacket, MspPacketData, MspPacketDataBuffer};
9
10use alloc::{borrow::ToOwned, string::String, vec::Vec};
11
12#[cfg(feature = "bincode")]
13use bincode::{Decode, Encode};
14use packed_struct::types::bits::ByteArray;
15use packed_struct::{PackedStruct, PackingError, PrimitiveEnum};
16
17#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
18#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
19pub struct MspApiVersion {
20    pub protocol_version: u8,
21    pub api_version_major: u8,
22    pub api_version_minor: u8,
23}
24
25#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
26#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
27pub struct MspFlightControllerVariant {
28    pub identifier: [u8; 4],
29}
30
31#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
32#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
33pub struct MspFlightControllerVersion {
34    pub major: u8,
35    pub minor: u8,
36    pub patch: u8,
37}
38
39#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
40#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
41#[packed_struct(endian = "lsb")]
42pub struct MspBoardInfo {
43    pub board_id: [u8; 4],
44    pub hardware_revision: u16,
45    pub fc_type: u8,
46}
47
48#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
49#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
50pub struct MspBuildInfo {
51    pub date_str: [u8; 11],
52    pub time_str: [u8; 8],
53    pub git_str: [u8; 7],
54}
55
56#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
57#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
58pub struct MspUniqueId {
59    pub uid: [u8; 12],
60}
61
62#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
63#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
64#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
65pub struct MspAvailableSensors {
66    #[packed_field(bits = "2")]
67    pub sonar: bool,
68    #[packed_field(bits = "4")]
69    pub gps: bool,
70    #[packed_field(bits = "5")]
71    pub mag: bool,
72    #[packed_field(bits = "6")]
73    pub baro: bool,
74    #[packed_field(bits = "7")]
75    pub acc: bool,
76}
77
78#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
79#[derive(Serialize, Deserialize, Debug, Copy, Clone, Default, PartialEq, Eq)]
80pub struct MspStatusSensors {
81    pub acc: bool,
82    pub baro: bool,
83    pub mag: bool,
84    pub gps: bool,
85    pub rangefinder: bool,
86    pub gyro: bool,
87    pub optical_flow: bool,
88}
89
90impl MspStatusSensors {
91    pub fn from_bits(bits: u16) -> Self {
92        Self {
93            acc: bits & (1 << 0) != 0,
94            baro: bits & (1 << 1) != 0,
95            mag: bits & (1 << 2) != 0,
96            gps: bits & (1 << 3) != 0,
97            rangefinder: bits & (1 << 4) != 0,
98            gyro: bits & (1 << 5) != 0,
99            optical_flow: bits & (1 << 6) != 0,
100        }
101    }
102
103    pub fn to_bits(self) -> u16 {
104        (self.acc as u16)
105            | (self.baro as u16) << 1
106            | (self.mag as u16) << 2
107            | (self.gps as u16) << 3
108            | (self.rangefinder as u16) << 4
109            | (self.gyro as u16) << 5
110            | (self.optical_flow as u16) << 6
111    }
112}
113
114impl From<u16> for MspStatusSensors {
115    fn from(bits: u16) -> Self {
116        Self::from_bits(bits)
117    }
118}
119
120impl From<MspStatusSensors> for u16 {
121    fn from(value: MspStatusSensors) -> Self {
122        value.to_bits()
123    }
124}
125
126#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
127#[derive(Serialize, Deserialize, Debug, Clone, Default, PartialEq)]
128pub struct MspStatus {
129    pub cycle_time: u16,
130    pub i2c_errors: u16,
131    pub sensors: MspStatusSensors,
132    pub flight_mode_flags: u32,
133    pub current_pid_profile_index: u8,
134    pub average_system_load_percent: u16,
135    pub gyro_cycle_time: u16,
136    pub extra_flight_mode_flags: Vec<u8>,
137    pub arming_disable_flags_count: u8,
138    pub arming_disable_flags: u32,
139    pub config_state_flags: u8,
140    pub core_temp_celsius: u16,
141    pub control_rate_profile_count: u8,
142}
143
144#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
145#[derive(Serialize, Deserialize, Debug, Clone, Default, PartialEq)]
146pub struct MspStatusEx {
147    pub cycle_time: u16,
148    pub i2c_errors: u16,
149    pub sensors: MspStatusSensors,
150    pub flight_mode_flags: u32,
151    pub current_pid_profile_index: u8,
152    pub average_system_load_percent: u16,
153    pub max_profile_count: u8,
154    pub current_control_rate_profile_index: u8,
155    pub extra_flight_mode_flags: Vec<u8>,
156    pub arming_disable_flags_count: u8,
157    pub arming_disable_flags: u32,
158    pub config_state_flags: u8,
159    pub core_temp_celsius: u16,
160    pub control_rate_profile_count: u8,
161}
162
163impl MspStatus {
164    pub fn from_bytes(data: &[u8]) -> Result<Self, PackingError> {
165        let mut offset = 0;
166        let cycle_time = read_u16(data, &mut offset)?;
167        let i2c_errors = read_u16(data, &mut offset)?;
168        let sensors = MspStatusSensors::from(read_u16(data, &mut offset)?);
169        let flight_mode_flags = read_u32(data, &mut offset)?;
170        let current_pid_profile_index = read_u8(data, &mut offset)?;
171        let average_system_load_percent = read_u16(data, &mut offset)?;
172        let gyro_cycle_time = read_u16(data, &mut offset)?;
173        let extra_flight_mode_flags_len = read_u8(data, &mut offset)? as usize;
174        let extra_flight_mode_flags = read_bytes(data, &mut offset, extra_flight_mode_flags_len)?;
175        let arming_disable_flags_count = read_u8(data, &mut offset)?;
176        let arming_disable_flags = read_u32(data, &mut offset)?;
177        let config_state_flags = read_u8(data, &mut offset)?;
178        let core_temp_celsius = read_u16(data, &mut offset)?;
179        let control_rate_profile_count = read_u8(data, &mut offset)?;
180
181        Ok(Self {
182            cycle_time,
183            i2c_errors,
184            sensors,
185            flight_mode_flags,
186            current_pid_profile_index,
187            average_system_load_percent,
188            gyro_cycle_time,
189            extra_flight_mode_flags,
190            arming_disable_flags_count,
191            arming_disable_flags,
192            config_state_flags,
193            core_temp_celsius,
194            control_rate_profile_count,
195        })
196    }
197
198    pub fn to_packet_data(&self) -> Result<MspPacketData, PackingError> {
199        if self.extra_flight_mode_flags.len() > 15 {
200            return Err(PackingError::InvalidValue);
201        }
202        let mut data = MspPacketDataBuffer::new();
203        extend_payload(&mut data, &self.cycle_time.to_le_bytes())?;
204        extend_payload(&mut data, &self.i2c_errors.to_le_bytes())?;
205        extend_payload(&mut data, &u16::from(self.sensors).to_le_bytes())?;
206        extend_payload(&mut data, &self.flight_mode_flags.to_le_bytes())?;
207        push_payload(&mut data, self.current_pid_profile_index)?;
208        extend_payload(&mut data, &self.average_system_load_percent.to_le_bytes())?;
209        extend_payload(&mut data, &self.gyro_cycle_time.to_le_bytes())?;
210        push_payload(&mut data, self.extra_flight_mode_flags.len() as u8)?;
211        extend_payload(&mut data, &self.extra_flight_mode_flags)?;
212        push_payload(&mut data, self.arming_disable_flags_count)?;
213        extend_payload(&mut data, &self.arming_disable_flags.to_le_bytes())?;
214        push_payload(&mut data, self.config_state_flags)?;
215        extend_payload(&mut data, &self.core_temp_celsius.to_le_bytes())?;
216        push_payload(&mut data, self.control_rate_profile_count)?;
217
218        Ok(MspPacketData(data))
219    }
220}
221
222impl MspStatusEx {
223    pub fn from_bytes(data: &[u8]) -> Result<Self, PackingError> {
224        let mut offset = 0;
225        let cycle_time = read_u16(data, &mut offset)?;
226        let i2c_errors = read_u16(data, &mut offset)?;
227        let sensors = MspStatusSensors::from(read_u16(data, &mut offset)?);
228        let flight_mode_flags = read_u32(data, &mut offset)?;
229        let current_pid_profile_index = read_u8(data, &mut offset)?;
230        let average_system_load_percent = read_u16(data, &mut offset)?;
231        let max_profile_count = read_u8(data, &mut offset)?;
232        let current_control_rate_profile_index = read_u8(data, &mut offset)?;
233        let extra_flight_mode_flags_len = read_u8(data, &mut offset)? as usize;
234        let extra_flight_mode_flags = read_bytes(data, &mut offset, extra_flight_mode_flags_len)?;
235        let arming_disable_flags_count = read_u8(data, &mut offset)?;
236        let arming_disable_flags = read_u32(data, &mut offset)?;
237        let config_state_flags = read_u8(data, &mut offset)?;
238        let core_temp_celsius = read_u16(data, &mut offset)?;
239        let control_rate_profile_count = read_u8(data, &mut offset)?;
240
241        Ok(Self {
242            cycle_time,
243            i2c_errors,
244            sensors,
245            flight_mode_flags,
246            current_pid_profile_index,
247            average_system_load_percent,
248            max_profile_count,
249            current_control_rate_profile_index,
250            extra_flight_mode_flags,
251            arming_disable_flags_count,
252            arming_disable_flags,
253            config_state_flags,
254            core_temp_celsius,
255            control_rate_profile_count,
256        })
257    }
258
259    pub fn to_packet_data(&self) -> Result<MspPacketData, PackingError> {
260        if self.extra_flight_mode_flags.len() > 15 {
261            return Err(PackingError::InvalidValue);
262        }
263        let mut data = MspPacketDataBuffer::new();
264        extend_payload(&mut data, &self.cycle_time.to_le_bytes())?;
265        extend_payload(&mut data, &self.i2c_errors.to_le_bytes())?;
266        extend_payload(&mut data, &u16::from(self.sensors).to_le_bytes())?;
267        extend_payload(&mut data, &self.flight_mode_flags.to_le_bytes())?;
268        push_payload(&mut data, self.current_pid_profile_index)?;
269        extend_payload(&mut data, &self.average_system_load_percent.to_le_bytes())?;
270        push_payload(&mut data, self.max_profile_count)?;
271        push_payload(&mut data, self.current_control_rate_profile_index)?;
272        push_payload(&mut data, self.extra_flight_mode_flags.len() as u8)?;
273        extend_payload(&mut data, &self.extra_flight_mode_flags)?;
274        push_payload(&mut data, self.arming_disable_flags_count)?;
275        extend_payload(&mut data, &self.arming_disable_flags.to_le_bytes())?;
276        push_payload(&mut data, self.config_state_flags)?;
277        extend_payload(&mut data, &self.core_temp_celsius.to_le_bytes())?;
278        push_payload(&mut data, self.control_rate_profile_count)?;
279
280        Ok(MspPacketData(data))
281    }
282}
283
284fn push_payload(data: &mut MspPacketDataBuffer, value: u8) -> Result<(), PackingError> {
285    let next_len = data.len() + 1;
286    if next_len > MSP_MAX_PAYLOAD_LEN {
287        return Err(PackingError::BufferSizeMismatch {
288            expected: MSP_MAX_PAYLOAD_LEN,
289            actual: next_len,
290        });
291    }
292    data.push(value)
293        .map_err(|_| PackingError::BufferSizeMismatch {
294            expected: MSP_MAX_PAYLOAD_LEN,
295            actual: next_len,
296        })?;
297    Ok(())
298}
299
300fn extend_payload(data: &mut MspPacketDataBuffer, bytes: &[u8]) -> Result<(), PackingError> {
301    let next_len = data.len() + bytes.len();
302    if next_len > MSP_MAX_PAYLOAD_LEN {
303        return Err(PackingError::BufferSizeMismatch {
304            expected: MSP_MAX_PAYLOAD_LEN,
305            actual: next_len,
306        });
307    }
308    data.extend_from_slice(bytes)
309        .map_err(|_| PackingError::BufferSizeMismatch {
310            expected: MSP_MAX_PAYLOAD_LEN,
311            actual: next_len,
312        })?;
313    Ok(())
314}
315
316fn read_u8(data: &[u8], offset: &mut usize) -> Result<u8, PackingError> {
317    if *offset + 1 > data.len() {
318        return Err(PackingError::BufferSizeMismatch {
319            expected: *offset + 1,
320            actual: data.len(),
321        });
322    }
323    let value = data[*offset];
324    *offset += 1;
325    Ok(value)
326}
327
328fn read_u16(data: &[u8], offset: &mut usize) -> Result<u16, PackingError> {
329    if *offset + 2 > data.len() {
330        return Err(PackingError::BufferSizeMismatch {
331            expected: *offset + 2,
332            actual: data.len(),
333        });
334    }
335    let value = u16::from_le_bytes([data[*offset], data[*offset + 1]]);
336    *offset += 2;
337    Ok(value)
338}
339
340fn read_u32(data: &[u8], offset: &mut usize) -> Result<u32, PackingError> {
341    if *offset + 4 > data.len() {
342        return Err(PackingError::BufferSizeMismatch {
343            expected: *offset + 4,
344            actual: data.len(),
345        });
346    }
347    let value = u32::from_le_bytes([
348        data[*offset],
349        data[*offset + 1],
350        data[*offset + 2],
351        data[*offset + 3],
352    ]);
353    *offset += 4;
354    Ok(value)
355}
356
357fn read_bytes(data: &[u8], offset: &mut usize, len: usize) -> Result<Vec<u8>, PackingError> {
358    if *offset + len > data.len() {
359        return Err(PackingError::BufferSizeMismatch {
360            expected: *offset + len,
361            actual: data.len(),
362        });
363    }
364    let bytes = data[*offset..*offset + len].to_vec();
365    *offset += len;
366    Ok(bytes)
367}
368
369#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
370#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
371#[packed_struct(endian = "lsb")]
372pub struct MspBfConfig {
373    pub mixer_configuration: u8,
374    pub features: u32,
375    pub serial_rx_provider: u8,
376    pub board_align_roll: i16,
377    pub board_align_pitch: i16,
378    pub board_align_yaw: i16,
379    pub current_scale: i16,
380    pub current_offset: i16,
381}
382
383#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
384#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
385#[packed_struct(endian = "lsb")]
386pub struct MspRawImu {
387    pub acc_x: i16,
388    pub acc_y: i16,
389    pub acc_z: i16,
390    pub gyro_x: i16,
391    pub gyro_y: i16,
392    pub gyro_z: i16,
393    pub mag_x: i16,
394    pub mag_y: i16,
395    pub mag_z: i16,
396}
397
398#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
399#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
400#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
401pub struct MspDataFlashSummaryReply {
402    #[packed_field(bits = "6")]
403    pub supported: bool,
404    #[packed_field(bits = "7")]
405    pub ready: bool,
406    pub sectors: u32,
407    pub total_size_bytes: u32,
408    pub used_size_bytes: u32,
409}
410
411#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
412#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
413#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
414pub struct MspDataFlashReply {
415    pub read_address: u32,
416    // pub payload: Vec<u8>, // TODO: packed_struct should support dynamic size too the end
417}
418
419#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
420#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
421#[packed_struct(bytes = "6", endian = "lsb", bit_numbering = "msb0")]
422pub struct MspDataFlashRead {
423    pub read_address: u32,
424    pub read_length: u16,
425}
426
427#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
428#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
429#[packed_struct(endian = "lsb")]
430pub struct MspAccTrim {
431    pub pitch: u16,
432    pub roll: u16,
433}
434
435#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
436#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
437#[packed_struct(endian = "lsb")]
438pub struct MspIdent {
439    pub version: u8,
440    pub mixer_mode: u8,
441    pub protocol_version: u8,
442    pub capability: u32,
443}
444
445#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
446#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
447#[packed_struct(endian = "lsb")]
448pub struct MspMisc {
449    pub rx_mid_rc: u16,
450    pub min_throttle: u16,
451    pub max_throttle: u16,
452    pub min_command: u16,
453    pub failsafe_throttle: u16,
454
455    pub gps_type: u8,
456    pub gps_baudrate: u8,
457    pub gps_sbas_mode: u8,
458
459    pub current_meter_output: u8,
460    pub rssi_channel: u8,
461    pub null1: u8,
462
463    pub compass_mag_declination: u16,
464}
465
466#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
467#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
468#[packed_struct(endian = "lsb")]
469pub struct MspAttitude {
470    pub roll: i16,
471    pub pitch: i16,
472    pub yaw: i16,
473}
474
475#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
476#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
477#[packed_struct(endian = "lsb")]
478pub struct MspAltitude {
479    /// [centimeters]
480    pub altitude: i32,
481    /// variometer [cm/s]
482    pub vario: i16,
483}
484
485#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
486#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
487#[packed_struct(endian = "lsb")]
488pub struct MspSensorRangefinder {
489    pub quality: u8,
490    pub distance_mm: i32,
491}
492
493#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
494#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
495#[packed_struct(endian = "lsb")]
496pub struct MspSensorOpticFlow {
497    pub quality: u8,
498    pub motion_x: i32,
499    pub motion_y: i32,
500}
501
502#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
503#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
504#[packed_struct(endian = "lsb")]
505pub struct MspBatteryConfig {
506    pub vbat_min_cell_voltage: u8,
507    pub vbat_max_cell_voltage: u8,
508    pub vbat_warning_cell_voltage: u8,
509    pub battery_capacity: u16,
510    pub voltage_meter_source: u8,
511    pub current_meter_source: u8,
512    pub vbat_min_cell_voltage_mv: u16,
513    pub vbat_max_cell_voltage_mv: u16,
514    pub vbat_warning_cell_voltage_mv: u16,
515}
516
517#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
518#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
519#[packed_struct(endian = "lsb")]
520pub struct MspVoltageMeterConfig {
521    pub sensor_count: u8,
522    pub subframe_len: u8,
523    pub id: u8,
524    pub sensor_type: u8,
525    pub vbat_scale: u8,
526    pub vbat_res_div_val: u8,
527    pub vbat_res_div_mult: u8,
528}
529
530#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
531#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
532#[packed_struct(endian = "lsb")]
533pub struct MspAnalog {
534    pub battery_voltage: u8,
535    pub mah_drawn: u16,
536    pub rssi: u16,
537    /// Current in 0.01A steps, range is -320A to 320A
538    pub amperage: i16,
539    /// Battery voltage in 0.01V steps
540    pub battery_voltage_mv: u16,
541}
542
543#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
544#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
545#[packed_struct(endian = "lsb")]
546pub struct MspRssiConfig {
547    pub rssi_channel: u8,
548}
549
550#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
551#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
552pub struct MspVoltageMeter {
553    pub id: u8,
554    pub value: u8,
555}
556
557#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
558#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
559#[packed_struct(endian = "lsb")]
560pub struct MspCurrentMeter {
561    pub id: u8,
562    pub mah_drawn: u16,
563    /// In 0.001A steps (mA)
564    pub amperage: u16,
565}
566
567#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
568#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
569#[packed_struct(endian = "lsb")]
570pub struct MspBatteryState {
571    pub battery_cell_count: u8,
572    /// mAh
573    pub battery_capacity: u16,
574
575    pub battery_voltage: u8,
576    pub mah_drawn: u16,
577    /// 0.01A
578    pub amperage: i16,
579
580    pub alerts: u8,
581    /// Battery voltage in 0.01V steps
582    pub battery_voltage_mv: u16,
583}
584
585impl MspBatteryState {
586    pub fn cell_voltage(&self) -> f32 {
587        self.battery_voltage as f32 / (10 * self.battery_cell_count) as f32
588    }
589}
590
591#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
592#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
593#[packed_struct(endian = "lsb")]
594pub struct MspRcTuning {
595    pub rc_rate8: u8,
596    pub rc_expo8: u8,
597
598    pub rate_roll: u8,
599    pub rate_pitch: u8,
600    pub rate_yaw: u8,
601
602    pub dyn_thr_pid: u8,
603    pub thr_mid8: u8,
604    pub thr_expo8: u8,
605    pub tpa_breakpoint: u16,
606    pub rc_yaw_expo8: u8,
607    pub rc_yaw_rate8: u8,
608}
609
610#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
611#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
612#[packed_struct(endian = "lsb")]
613pub struct MspRxConfig {
614    pub serialrx_provider: u8,
615    pub maxcheck: u16,
616    pub midrc: u16,
617    pub mincheck: u16,
618    pub spektrum_sat_bind: u8,
619    pub rx_min_usec: u16,
620    pub rx_max_usec: u16,
621    pub rc_interpolation: u8,
622    pub rc_interpolation_interval: u8,
623    pub air_mode_activate_threshold: u16,
624    pub rx_spi_protocol: u8,
625    pub rx_spi_id: u32,
626    pub rx_spi_rf_channel_count: u8,
627    pub fpv_cam_angle_degrees: u8,
628}
629
630#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
631#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
632#[packed_struct(endian = "lsb")]
633pub struct MspRcChannelValue {
634    pub value: u16,
635}
636
637#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
638#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
639pub enum MspRcChannel {
640    /// Ailerons
641    #[default]
642    Roll = 0,
643    /// Elevators
644    Pitch = 1,
645    /// Rudder
646    Yaw = 2,
647    Throttle = 3,
648    Aux1 = 4,
649    Aux2 = 5,
650    Aux3 = 6,
651    Aux4 = 7,
652    Aux5 = 8,
653    Aux6 = 9,
654    Aux7 = 10,
655    Aux8 = 11,
656    Aux9 = 12,
657    Aux10 = 13,
658    Aux11 = 14,
659    Aux12 = 15,
660    Aux13 = 16,
661    Aux14 = 17,
662    Aux15 = 18,
663    Aux16 = 19,
664}
665
666#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
667#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
668pub struct MspRcMappedChannel {
669    #[packed_field(size_bits = "8", ty = "enum")]
670    pub channel: MspRcChannel,
671}
672
673#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
674#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
675pub struct MspFeatures {
676    pub features: [bool; 32],
677}
678
679#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
680#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
681#[packed_struct(endian = "lsb")]
682pub struct MspMotor {
683    pub motors: [u16; 8],
684}
685
686#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
687#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
688#[packed_struct(endian = "lsb")]
689pub struct MspMotor3DConfig {
690    pub deadband_3d_low: u16,
691    pub deadband_3d_high: u16,
692    pub neutral_3d: u16,
693}
694
695#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
696#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
697#[packed_struct(endian = "lsb")]
698pub struct MspMotorConfig {
699    pub min_throttle: u16,
700    pub max_throttle: u16,
701    pub min_command: u16,
702}
703
704#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
705#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
706#[packed_struct(endian = "lsb")]
707pub struct MspRcDeadband {
708    pub deadband: u8,
709    pub yaw_deadband: u8,
710    pub alt_hold_deadband: u8,
711    pub deadband_3d_throttle: u16,
712}
713
714#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
715#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
716#[packed_struct(endian = "lsb")]
717pub struct MspSensorAlignment {
718    pub gyro_alignment: u8,
719    pub acc_alignment: u8,
720    pub mag_alignment: u8,
721}
722
723#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
724#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
725#[packed_struct(endian = "lsb")]
726pub struct MspAdvancedConfig {
727    pub gyro_sync_denom: u8,
728    pub pid_process_denom: u8,
729    pub use_unsynced_pwm: u8,
730    pub motor_pwm_protocol: u8,
731    pub motor_pwm_rate: u16,
732    pub digital_idle_offset_percent: u16,
733    pub gyro_use_32khz: u8,
734    pub motor_pwm_inversion: u8,
735}
736
737#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
738#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
739#[packed_struct(endian = "lsb")]
740pub struct MspFilterConfig {
741    pub gyro_soft_lpf_hz: u8,
742    pub dterm_lpf_hz: u16,
743    pub yaw_lpf_hz: u16,
744    pub gyro_soft_notch_hz_1: u16,
745    pub gyro_soft_notch_cutoff_1: u16,
746    pub dterm_notch_hz: u16,
747    pub dterm_notch_cutoff: u16,
748    pub gyro_soft_notch_hz_2: u16,
749    pub gyro_soft_notch_cutoff_2: u16,
750}
751
752#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
753#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
754#[packed_struct(endian = "lsb")]
755pub struct MspPidAdvanced {
756    pub _r1: u16,
757    pub _r2: u16,
758    pub _r3: u16,
759    pub _r4: u8,
760    pub vbat_pid_compensation: u8,
761    pub setpoint_relax_ratio: u8,
762    pub dterm_setpoint_weight: u8,
763    pub _r5: u8,
764    pub _r6: u8,
765    pub _r7: u8,
766    pub rate_accel_limit: u16,
767    pub yaw_rate_accel_limit: u16,
768    pub level_angle_limit: u8,
769    pub level_sensitivity: u8,
770}
771
772#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
773#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
774#[packed_struct(endian = "lsb")]
775pub struct MspSensorConfig {
776    pub acc_hardware: u8,
777    pub baro_hardware: u8,
778    pub mag_hardware: u8,
779}
780
781#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
782#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
783#[packed_struct(endian = "lsb")]
784pub struct MspServos {
785    pub servos: [u16; 8],
786}
787
788#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
789#[derive(PackedStruct, Debug, Copy, Clone, Default)]
790#[packed_struct(bytes = "14", endian = "lsb", bit_numbering = "msb0")]
791pub struct MspServoConfig {
792    pub min: u16,
793    pub max: u16,
794    pub middle: u16,
795    pub rate: i8,
796    pub unused1: u8,
797    pub unused2: u8,
798    pub forward_from_channel: u8, // Deprecated, set to 255 for backward compatibility
799    pub reverse_input: u32, // Deprecated, Input reversing is not required since it can be done on mixer level
800}
801
802#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
803#[derive(PackedStruct, Debug, Copy, Clone, Default)]
804#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
805pub struct MspSetServoConfig {
806    pub index: u8,
807    #[packed_field(size_bytes = "14")]
808    pub servo_config: MspServoConfig,
809}
810
811#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
812#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
813#[packed_struct(endian = "lsb")]
814pub struct MspMixerConfig {
815    #[packed_field(size_bits = "8", ty = "enum")]
816    pub mixer_mode: MixerMode,
817}
818
819#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
820#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
821#[packed_struct(bytes = "4", endian = "lsb", bit_numbering = "msb0")]
822pub struct MspModeRange {
823    pub box_id: u8,
824    #[packed_field(size_bits = "8", ty = "enum")]
825    pub aux_channel_index: MspRcChannel,
826    pub start_step: u8,
827    pub end_step: u8,
828}
829
830#[cfg_attr(feature = "bincode", derive(Decode, Encode, Default))]
831#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)]
832#[packed_struct(bytes = "5", endian = "lsb", bit_numbering = "msb0")]
833pub struct MspSetModeRange {
834    pub index: u8,
835    #[packed_field(size_bytes = "4")]
836    pub mode_range: MspModeRange,
837}
838
839#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
840#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
841pub enum MixerMode {
842    Tri = 1,
843    QuadPlus = 2,
844    #[default]
845    QuadX = 3,
846    Bicopter = 4,
847    Gimbal = 5,
848    Y6 = 6,
849    Hex6 = 7,
850    FlyingWing = 8,
851    Y4 = 9,
852    Hex6X = 10,
853    OctoX8 = 11,
854}
855
856#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
857#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
858#[packed_struct(bytes = "8", endian = "lsb", bit_numbering = "msb0")]
859pub struct MspMotorMixer {
860    pub throttle: u16,
861    pub roll: u16,
862    pub pitch: u16,
863    pub yaw: u16,
864}
865
866#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
867#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
868#[packed_struct(bytes = "9", endian = "lsb", bit_numbering = "msb0")]
869pub struct MspSetMotorMixer {
870    pub index: u8,
871    #[packed_field(size_bytes = "8")]
872    pub motor_mixer: MspMotorMixer,
873}
874
875pub const MSP_DP_HEARTBEAT: u8 = 0;
876pub const MSP_DP_RELEASE: u8 = 1;
877pub const MSP_DP_CLEAR_SCREEN: u8 = 2;
878pub const MSP_DP_WRITE_STRING: u8 = 3;
879pub const MSP_DP_DRAW_SCREEN: u8 = 4;
880pub const MSP_DP_OPTIONS: u8 = 5;
881pub const MSP_DP_SYS: u8 = 6;
882pub const MSP_DP_FONTCHAR_WRITE: u8 = 7;
883
884#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
885#[derive(Debug, Serialize, Deserialize, Clone, Default, PartialEq, Eq)]
886pub struct MspDisplayPort {
887    pub payload: Vec<u8>,
888}
889
890impl MspDisplayPort {
891    pub fn new(payload: Vec<u8>) -> Self {
892        Self { payload }
893    }
894
895    pub fn heartbeat() -> Self {
896        Self {
897            payload: Vec::from([MSP_DP_HEARTBEAT]),
898        }
899    }
900
901    pub fn release() -> Self {
902        Self {
903            payload: Vec::from([MSP_DP_RELEASE]),
904        }
905    }
906
907    pub fn clear_screen() -> Self {
908        Self {
909            payload: Vec::from([MSP_DP_CLEAR_SCREEN]),
910        }
911    }
912
913    pub fn draw_screen() -> Self {
914        Self {
915            payload: Vec::from([MSP_DP_DRAW_SCREEN]),
916        }
917    }
918
919    pub fn write_string(row: u8, col: u8, attr: u8, text: &str) -> Self {
920        let mut payload = Vec::with_capacity(4 + text.len());
921        payload.push(MSP_DP_WRITE_STRING);
922        payload.push(row);
923        payload.push(col);
924        payload.push(attr);
925        payload.extend_from_slice(text.as_bytes());
926        Self { payload }
927    }
928
929    pub fn sys(row: u8, col: u8, element: u8) -> Self {
930        Self {
931            payload: Vec::from([MSP_DP_SYS, row, col, element]),
932        }
933    }
934
935    pub fn as_bytes(&self) -> &[u8] {
936        &self.payload
937    }
938}
939
940#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
941#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
942#[packed_struct(bytes = "13", endian = "lsb", bit_numbering = "msb0")]
943pub struct MspOsdConfig {
944    pub video_system: u8,
945    pub units: u8,
946    pub rssi_alarm: u8,
947    pub capacity_warning: u16,
948    pub time_alarm: u16,
949    pub alt_alarm: u16,
950    pub dist_alarm: u16,
951    pub neg_alt_alarm: u16,
952}
953
954#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
955#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
956#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
957pub struct MspSetGetOsdConfig {
958    pub item_index: u8,
959    #[packed_field(size_bytes = "13")]
960    pub config: MspOsdConfig,
961}
962
963#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
964#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
965#[packed_struct(bytes = "2", endian = "lsb", bit_numbering = "msb0")]
966pub struct MspOsdItemPosition {
967    pub col: u8,
968    pub row: u8,
969}
970
971#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
972#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
973#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
974pub struct MspSetOsdLayout {
975    pub item_index: u8,
976    #[packed_field(size_bytes = "2")]
977    pub item: MspOsdItemPosition,
978}
979
980// inav msp layout item
981#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
982#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
983#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
984pub struct MspSetOsdLayoutItem {
985    pub layout_index: u8,
986    #[packed_field(size_bytes = "3")]
987    pub item: MspSetOsdLayout,
988}
989
990#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
991#[derive(Debug, Serialize, Deserialize, Clone, Default)]
992pub struct MspOsdSettings {
993    pub osd_support: u8,
994    pub config: MspOsdConfig,
995    pub item_positions: Vec<MspOsdItemPosition>,
996}
997
998#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
999#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1000#[packed_struct(bytes = "2", endian = "lsb", bit_numbering = "msb0")]
1001pub struct MspOsdLayouts {
1002    pub layout_count: u8,
1003    pub item_count: u8,
1004}
1005
1006#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1007#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
1008pub enum SerialIdentifier {
1009    #[default]
1010    None = 255,
1011    USART1 = 0,
1012    USART2 = 1,
1013    USART3 = 2,
1014    USART4 = 3,
1015    USART5 = 4,
1016    USART6 = 5,
1017    USART7 = 6,
1018    USART8 = 7,
1019    UsbVcp = 20,
1020    SoftSerial1 = 30,
1021    SoftSerial2 = 31,
1022}
1023
1024impl TryFrom<u8> for SerialIdentifier {
1025    type Error = &'static str;
1026
1027    fn try_from(value: u8) -> Result<Self, Self::Error> {
1028        let serial = match value {
1029            255 => SerialIdentifier::None,
1030            0 => SerialIdentifier::USART1,
1031            1 => SerialIdentifier::USART2,
1032            2 => SerialIdentifier::USART3,
1033            3 => SerialIdentifier::USART4,
1034            4 => SerialIdentifier::USART5,
1035            5 => SerialIdentifier::USART6,
1036            6 => SerialIdentifier::USART7,
1037            7 => SerialIdentifier::USART8,
1038            20 => SerialIdentifier::UsbVcp,
1039            30 => SerialIdentifier::SoftSerial1,
1040            31 => SerialIdentifier::SoftSerial2,
1041            _ => return Err("Serial identifier not found"),
1042        };
1043
1044        Ok(serial)
1045    }
1046}
1047
1048#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1049#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
1050pub enum Baudrate {
1051    #[default]
1052    BaudAuto = 0,
1053    Baud1200 = 1,
1054    Baud2400 = 2,
1055    Baud4800 = 3,
1056    Baud9600 = 4,
1057    Baud19200 = 5,
1058    Baud38400 = 6,
1059    Baud57600 = 7,
1060    Baud115200 = 8,
1061    Baud230400 = 9,
1062    Baud250000 = 10,
1063    Baud460800 = 11,
1064    Baud921600 = 12,
1065    Baud1000000 = 13,
1066    Baud1500000 = 14,
1067    Baud2000000 = 15,
1068    Baud2470000 = 16,
1069}
1070
1071impl TryFrom<&str> for Baudrate {
1072    type Error = &'static str;
1073
1074    fn try_from(value: &str) -> Result<Self, Self::Error> {
1075        let baudrate = match value {
1076            "0" => Baudrate::BaudAuto,
1077            "1200" => Baudrate::Baud1200,
1078            "2400" => Baudrate::Baud2400,
1079            "4800" => Baudrate::Baud4800,
1080            "9600" => Baudrate::Baud9600,
1081            "19200" => Baudrate::Baud19200,
1082            "38400" => Baudrate::Baud38400,
1083            "57600" => Baudrate::Baud57600,
1084            "115200" => Baudrate::Baud115200,
1085            "230400" => Baudrate::Baud230400,
1086            "250000" => Baudrate::Baud250000,
1087            "460800" => Baudrate::Baud460800,
1088            "921600" => Baudrate::Baud921600,
1089            "1000000" => Baudrate::Baud1000000,
1090            "1500000" => Baudrate::Baud1500000,
1091            "2000000" => Baudrate::Baud2000000,
1092            "2470000" => Baudrate::Baud2470000,
1093            _ => return Err("Baudrate identifier not found"),
1094        };
1095
1096        Ok(baudrate)
1097    }
1098}
1099
1100impl From<Baudrate> for String {
1101    fn from(value: Baudrate) -> Self {
1102        match value {
1103            Baudrate::BaudAuto => "0",
1104            Baudrate::Baud1200 => "1200",
1105            Baudrate::Baud2400 => "2400",
1106            Baudrate::Baud4800 => "4800",
1107            Baudrate::Baud9600 => "9600",
1108            Baudrate::Baud19200 => "19200",
1109            Baudrate::Baud38400 => "38400",
1110            Baudrate::Baud57600 => "57600",
1111            Baudrate::Baud115200 => "115200",
1112            Baudrate::Baud230400 => "230400",
1113            Baudrate::Baud250000 => "250000",
1114            Baudrate::Baud460800 => "460800",
1115            Baudrate::Baud921600 => "921600",
1116            Baudrate::Baud1000000 => "1000000",
1117            Baudrate::Baud1500000 => "1500000",
1118            Baudrate::Baud2000000 => "2000000",
1119            Baudrate::Baud2470000 => "2470000",
1120        }
1121        .to_owned()
1122    }
1123}
1124
1125#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1126#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1127#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
1128pub struct MspSerialSetting {
1129    #[packed_field(size_bits = "8", ty = "enum")]
1130    pub identifier: SerialIdentifier,
1131    pub function_mask: u32,
1132    #[packed_field(size_bits = "8", ty = "enum")]
1133    pub msp_baudrate_index: Baudrate,
1134    #[packed_field(size_bits = "8", ty = "enum")]
1135    pub gps_baudrate_index: Baudrate,
1136    #[packed_field(size_bits = "8", ty = "enum")]
1137    pub telemetry_baudrate_index: Baudrate,
1138    #[packed_field(size_bits = "8", ty = "enum")]
1139    pub peripheral_baudrate_index: Baudrate,
1140}
1141
1142#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1143#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1144#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
1145pub struct MspSetServoMixRule {
1146    pub index: u8,
1147    #[packed_field(size_bytes = "8")]
1148    pub servo_rule: MspServoMixRule,
1149}
1150
1151#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1152#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1153#[packed_struct(bytes = "8", endian = "lsb", bit_numbering = "msb0")]
1154pub struct MspServoMixRule {
1155    pub target_channel: u8,
1156    pub input_source: u8,
1157    pub rate: u16,
1158    pub speed: u8,
1159    pub min: u8,
1160    pub max: u8,
1161    pub box_id: u8,
1162}
1163
1164#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1165#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1166#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
1167pub struct MspSetServoMixer {
1168    pub index: u8,
1169    #[packed_field(size_bytes = "6")]
1170    pub servo_rule: MspServoMixer,
1171}
1172
1173#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1174#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1175#[packed_struct(bytes = "6", endian = "lsb", bit_numbering = "msb0")]
1176pub struct MspServoMixer {
1177    pub target_channel: u8,
1178    pub input_source: u8,
1179    pub rate: i16,
1180    pub speed: u8,
1181    pub condition_id: i8,
1182}
1183
1184#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1185#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1186#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
1187pub struct MspRxMap {
1188    pub map: [u8; 4], // MAX_MAPPABLE_RX_INPUTS
1189}
1190
1191#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1192#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1193#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
1194pub struct MspSettingGroup {
1195    pub group_id: u16,
1196    pub start_id: u16,
1197    pub end_id: u16,
1198}
1199
1200#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1201#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1202#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
1203pub struct MspSettingInfoRequest {
1204    pub null: u8,
1205    pub id: u16,
1206}
1207
1208#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1209#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
1210pub enum SettingMode {
1211    #[default]
1212    ModeDirect = 0,
1213    ModeLookup = 0x40,
1214}
1215
1216#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1217#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
1218pub enum SettingType {
1219    #[default]
1220    VarUint8 = 0,
1221    VarInt8,
1222    VarUint16,
1223    VarInt16,
1224    VarUint32,
1225    VarInt32,
1226    VarFloat,
1227    VarString,
1228}
1229
1230#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1231#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
1232#[packed_struct(bytes = "15", endian = "lsb", bit_numbering = "msb0")]
1233pub struct MspSettingInfo {
1234    // pub name: [u8; ?], null terminated strings
1235
1236    // Parameter Group ID
1237    pub group_id: u16,
1238
1239    // Type, section and mode
1240    #[packed_field(size_bits = "8", ty = "enum")]
1241    pub setting_type: SettingType,
1242    pub setting_section: u8,
1243    #[packed_field(size_bits = "8", ty = "enum")]
1244    pub setting_mode: SettingMode,
1245
1246    pub min: u32,
1247    pub max: u32,
1248
1249    // Absolute setting index
1250    pub absolute_index: u16,
1251
1252    // If the setting is profile based, send the current one
1253    // and the count, both as uint8_t. For MASTER_VALUE, we
1254    // send two zeroes, so the MSP client can assume there
1255    pub profile_id: u8,
1256    pub profile_count: u8,
1257    // if setting uses enum values, it will be written here
1258    // pub enum_names: [String; ?] // TODO: packed_struct should support null terminated string parsing
1259    // pub value: [u8; ?]
1260}
1261
1262#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1263#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)]
1264#[packed_struct(endian = "lsb")]
1265pub struct MspRc {
1266    pub channels: [u16; 16], // 16 RC channels
1267}
1268
1269impl Default for MspRc {
1270    fn default() -> Self {
1271        Self::new()
1272    }
1273}
1274
1275impl MspRc {
1276    pub fn new() -> Self {
1277        MspRc { channels: [0; 16] }
1278    }
1279
1280    pub fn set_roll(&mut self, value: u16) {
1281        self.channels[0] = value;
1282    }
1283
1284    pub fn set_pitch(&mut self, value: u16) {
1285        self.channels[1] = value;
1286    }
1287
1288    pub fn set_throttle(&mut self, value: u16) {
1289        self.channels[2] = value;
1290    }
1291
1292    pub fn set_yaw(&mut self, value: u16) {
1293        self.channels[3] = value;
1294    }
1295
1296    pub fn set_aux1(&mut self, value: u16) {
1297        self.channels[4] = value;
1298    }
1299    pub fn set_aux2(&mut self, value: u16) {
1300        self.channels[5] = value;
1301    }
1302    pub fn set_aux3(&mut self, value: u16) {
1303        self.channels[6] = value;
1304    }
1305    pub fn set_aux4(&mut self, value: u16) {
1306        self.channels[7] = value;
1307    }
1308}
1309
1310// Gather all the commands in a common enum we can use as a higher level protocol
1311#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1312#[derive(Debug, Clone, Default, Serialize, Deserialize)]
1313pub enum MspRequest {
1314    #[default]
1315    Unknown,
1316    MspApiVersionRequest,
1317    MspApiVersion(MspApiVersion),
1318    MspFcVersionRequest,
1319    MspFlightControllerVersion(MspFlightControllerVersion),
1320    MspBatteryConfigRequest,
1321    MspBatteryConfig(MspBatteryConfig),
1322    MspBatteryStateRequest,
1323    MspBatteryState(MspBatteryState),
1324    MspAnalogRequest,
1325    MspAnalog(MspAnalog),
1326    MspVoltageMeterConfigRequest,
1327    MspVoltageMeterConfig(MspVoltageMeterConfig),
1328    MspVoltageMetersRequest,
1329    MspVoltageMeter(MspVoltageMeter),
1330    MspRc,
1331    MspSetRawRc(MspRc),
1332    MspRawImu,
1333    MspStatus(MspStatus),
1334    MspStatusEx(MspStatusEx),
1335    MspDisplayPort(MspDisplayPort),
1336    MspSensorRangefinder(MspSensorRangefinder),
1337    MspSensorOpticFlow(MspSensorOpticFlow),
1338}
1339
1340impl MspRequest {
1341    pub fn command_code(&self) -> MspCommandCode {
1342        match self {
1343            MspRequest::MspApiVersionRequest => MspCommandCode::MSP_API_VERSION,
1344            MspRequest::MspApiVersion(_) => MspCommandCode::MSP_API_VERSION,
1345            MspRequest::MspFcVersionRequest => MspCommandCode::MSP_FC_VERSION,
1346            MspRequest::MspFlightControllerVersion(_) => MspCommandCode::MSP_FC_VERSION,
1347            MspRequest::MspBatteryConfigRequest => MspCommandCode::MSP_BATTERY_CONFIG,
1348            MspRequest::MspBatteryConfig(_) => MspCommandCode::MSP_BATTERY_CONFIG,
1349            MspRequest::MspBatteryStateRequest => MspCommandCode::MSP_BATTERY_STATE,
1350            MspRequest::MspBatteryState(_) => MspCommandCode::MSP_BATTERY_STATE,
1351            MspRequest::MspAnalogRequest => MspCommandCode::MSP_ANALOG,
1352            MspRequest::MspAnalog(_) => MspCommandCode::MSP_ANALOG,
1353            MspRequest::MspVoltageMeterConfigRequest => MspCommandCode::MSP_VOLTAGE_METER_CONFIG,
1354            MspRequest::MspVoltageMeterConfig(_) => MspCommandCode::MSP_VOLTAGE_METER_CONFIG,
1355            MspRequest::MspVoltageMetersRequest => MspCommandCode::MSP_VOLTAGE_METERS,
1356            MspRequest::MspVoltageMeter(_) => MspCommandCode::MSP_VOLTAGE_METERS,
1357            MspRequest::MspRc => MspCommandCode::MSP_RC,
1358            MspRequest::MspSetRawRc(_) => MspCommandCode::MSP_SET_RAW_RC,
1359            MspRequest::MspRawImu => MspCommandCode::MSP_RAW_IMU,
1360            MspRequest::MspStatus(_) => MspCommandCode::MSP_STATUS,
1361            MspRequest::MspStatusEx(_) => MspCommandCode::MSP_STATUS_EX,
1362            MspRequest::MspDisplayPort(_) => MspCommandCode::MSP_DISPLAYPORT,
1363            MspRequest::MspSensorRangefinder(_) => MspCommandCode::MSP2_SENSOR_RANGEFINDER,
1364            MspRequest::MspSensorOpticFlow(_) => MspCommandCode::MSP2_SENSOR_OPTIC_FLOW,
1365            _ => MspCommandCode::MSP_API_VERSION,
1366        }
1367    }
1368
1369    pub fn from_command_code(cmd: MspCommandCode) -> Option<Self> {
1370        match cmd {
1371            MspCommandCode::MSP_API_VERSION => Some(MspRequest::MspApiVersionRequest),
1372            MspCommandCode::MSP_FC_VERSION => Some(MspRequest::MspFcVersionRequest),
1373            MspCommandCode::MSP_BATTERY_CONFIG => Some(MspRequest::MspBatteryConfigRequest),
1374            MspCommandCode::MSP_BATTERY_STATE => Some(MspRequest::MspBatteryStateRequest),
1375            MspCommandCode::MSP_ANALOG => Some(MspRequest::MspAnalogRequest),
1376            MspCommandCode::MSP_VOLTAGE_METER_CONFIG => {
1377                Some(MspRequest::MspVoltageMeterConfigRequest)
1378            }
1379            MspCommandCode::MSP_VOLTAGE_METERS => Some(MspRequest::MspVoltageMetersRequest),
1380            MspCommandCode::MSP_RC => Some(MspRequest::MspRc),
1381            MspCommandCode::MSP_RAW_IMU => Some(MspRequest::MspRawImu),
1382            _ => None,
1383        }
1384    }
1385
1386    pub fn from_command_id(cmd: u16) -> Option<Self> {
1387        let cmd = MspCommandCode::from_primitive(cmd)?;
1388        Self::from_command_code(cmd)
1389    }
1390
1391    pub fn from_packet(packet: &MspPacket) -> Option<Self> {
1392        let cmd = MspCommandCode::from_primitive(packet.cmd)?;
1393        match cmd {
1394            MspCommandCode::MSP2_SENSOR_RANGEFINDER => packet
1395                .decode_as::<MspSensorRangefinder>()
1396                .ok()
1397                .map(MspRequest::MspSensorRangefinder),
1398            MspCommandCode::MSP2_SENSOR_OPTIC_FLOW => packet
1399                .decode_as::<MspSensorOpticFlow>()
1400                .ok()
1401                .map(MspRequest::MspSensorOpticFlow),
1402            _ => Self::from_command_code(cmd),
1403        }
1404    }
1405}
1406
1407fn pack_or_empty<T: PackedStruct>(value: Option<&T>) -> Result<MspPacketData, PackingError> {
1408    if let Some(value) = value {
1409        let packed = value.pack()?;
1410        Ok(MspPacketData::from(packed.as_bytes_slice()))
1411    } else {
1412        Ok(MspPacketData::default())
1413    }
1414}
1415
1416impl From<MspRequest> for MspPacket {
1417    fn from(request: MspRequest) -> Self {
1418        match request {
1419            MspRequest::MspApiVersionRequest => MspPacket {
1420                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1421                direction: ToFlightController,
1422                data: MspPacketData::new(),
1423            },
1424            MspRequest::MspApiVersion(version) => MspPacket {
1425                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1426                direction: FromFlightController,
1427                data: pack_or_empty(Some(&version)).unwrap_or_default(),
1428            },
1429            MspRequest::MspFcVersionRequest => MspPacket {
1430                cmd: MspCommandCode::MSP_FC_VERSION.to_primitive(),
1431                direction: ToFlightController,
1432                data: MspPacketData::new(),
1433            },
1434            MspRequest::MspFlightControllerVersion(version) => MspPacket {
1435                cmd: MspCommandCode::MSP_FC_VERSION.to_primitive(),
1436                direction: FromFlightController,
1437                data: pack_or_empty(Some(&version)).unwrap_or_default(),
1438            },
1439            MspRequest::MspBatteryConfigRequest => MspPacket {
1440                cmd: MspCommandCode::MSP_BATTERY_CONFIG.to_primitive(),
1441                direction: ToFlightController,
1442                data: MspPacketData::new(),
1443            },
1444            MspRequest::MspBatteryConfig(config) => MspPacket {
1445                cmd: MspCommandCode::MSP_BATTERY_CONFIG.to_primitive(),
1446                direction: FromFlightController,
1447                data: pack_or_empty(Some(&config)).unwrap_or_default(),
1448            },
1449            MspRequest::MspBatteryStateRequest => MspPacket {
1450                cmd: MspCommandCode::MSP_BATTERY_STATE.to_primitive(),
1451                direction: ToFlightController,
1452                data: MspPacketData::new(), // empty
1453            },
1454            MspRequest::MspBatteryState(state) => MspPacket {
1455                cmd: MspCommandCode::MSP_BATTERY_STATE.to_primitive(),
1456                direction: FromFlightController,
1457                data: pack_or_empty(Some(&state)).unwrap_or_default(),
1458            },
1459            MspRequest::MspAnalogRequest => MspPacket {
1460                cmd: MspCommandCode::MSP_ANALOG.to_primitive(),
1461                direction: ToFlightController,
1462                data: MspPacketData::new(), // empty
1463            },
1464            MspRequest::MspAnalog(analog) => MspPacket {
1465                cmd: MspCommandCode::MSP_ANALOG.to_primitive(),
1466                direction: FromFlightController,
1467                data: pack_or_empty(Some(&analog)).unwrap_or_default(),
1468            },
1469            MspRequest::MspVoltageMeterConfigRequest => MspPacket {
1470                cmd: MspCommandCode::MSP_VOLTAGE_METER_CONFIG.to_primitive(),
1471                direction: ToFlightController,
1472                data: MspPacketData::new(),
1473            },
1474            MspRequest::MspVoltageMeterConfig(config) => MspPacket {
1475                cmd: MspCommandCode::MSP_VOLTAGE_METER_CONFIG.to_primitive(),
1476                direction: FromFlightController,
1477                data: pack_or_empty(Some(&config)).unwrap_or_default(),
1478            },
1479            MspRequest::MspVoltageMetersRequest => MspPacket {
1480                cmd: MspCommandCode::MSP_VOLTAGE_METERS.to_primitive(),
1481                direction: ToFlightController,
1482                data: MspPacketData::new(), // empty
1483            },
1484            MspRequest::MspVoltageMeter(meter) => MspPacket {
1485                cmd: MspCommandCode::MSP_VOLTAGE_METERS.to_primitive(),
1486                direction: FromFlightController,
1487                data: pack_or_empty(Some(&meter)).unwrap_or_default(),
1488            },
1489            MspRequest::MspRc => MspPacket {
1490                cmd: MspCommandCode::MSP_RC.to_primitive(),
1491                direction: ToFlightController,
1492                data: MspPacketData::new(), // empty
1493            },
1494            MspRequest::MspSetRawRc(rc) => {
1495                let data = rc.pack().unwrap();
1496                MspPacket {
1497                    cmd: MspCommandCode::MSP_SET_RAW_RC.to_primitive(),
1498                    direction: ToFlightController,
1499                    data: MspPacketData::from(data.as_slice()),
1500                }
1501            }
1502            MspRequest::MspRawImu => MspPacket {
1503                cmd: MspCommandCode::MSP_RAW_IMU.to_primitive(),
1504                direction: ToFlightController,
1505                data: MspPacketData::new(), // empty
1506            },
1507            MspRequest::MspStatus(status) => MspPacket {
1508                cmd: MspCommandCode::MSP_STATUS.to_primitive(),
1509                direction: FromFlightController,
1510                data: status.to_packet_data().unwrap(),
1511            },
1512            MspRequest::MspStatusEx(status) => MspPacket {
1513                cmd: MspCommandCode::MSP_STATUS_EX.to_primitive(),
1514                direction: FromFlightController,
1515                data: status.to_packet_data().unwrap(),
1516            },
1517            MspRequest::MspDisplayPort(displayport) => MspPacket {
1518                cmd: MspCommandCode::MSP_DISPLAYPORT.to_primitive(),
1519                direction: FromFlightController,
1520                data: MspPacketData::from(displayport.as_bytes()),
1521            },
1522            MspRequest::MspSensorRangefinder(data) => MspPacket {
1523                cmd: MspCommandCode::MSP2_SENSOR_RANGEFINDER.to_primitive(),
1524                direction: ToFlightController,
1525                data: pack_or_empty(Some(&data)).unwrap_or_default(),
1526            },
1527            MspRequest::MspSensorOpticFlow(data) => MspPacket {
1528                cmd: MspCommandCode::MSP2_SENSOR_OPTIC_FLOW.to_primitive(),
1529                direction: ToFlightController,
1530                data: pack_or_empty(Some(&data)).unwrap_or_default(),
1531            },
1532            _ => MspPacket {
1533                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1534                direction: ToFlightController,
1535                data: MspPacketData::new(), // empty
1536            },
1537        }
1538    }
1539}
1540
1541impl From<&MspRequest> for MspPacket {
1542    fn from(request: &MspRequest) -> Self {
1543        match request {
1544            MspRequest::MspApiVersionRequest => MspPacket {
1545                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1546                direction: ToFlightController,
1547                data: MspPacketData::new(),
1548            },
1549            MspRequest::MspApiVersion(version) => MspPacket {
1550                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1551                direction: FromFlightController,
1552                data: pack_or_empty(Some(version)).unwrap_or_default(),
1553            },
1554            MspRequest::MspFcVersionRequest => MspPacket {
1555                cmd: MspCommandCode::MSP_FC_VERSION.to_primitive(),
1556                direction: ToFlightController,
1557                data: MspPacketData::new(),
1558            },
1559            MspRequest::MspFlightControllerVersion(version) => MspPacket {
1560                cmd: MspCommandCode::MSP_FC_VERSION.to_primitive(),
1561                direction: FromFlightController,
1562                data: pack_or_empty(Some(version)).unwrap_or_default(),
1563            },
1564            MspRequest::MspBatteryConfigRequest => MspPacket {
1565                cmd: MspCommandCode::MSP_BATTERY_CONFIG.to_primitive(),
1566                direction: ToFlightController,
1567                data: MspPacketData::new(),
1568            },
1569            MspRequest::MspBatteryConfig(config) => MspPacket {
1570                cmd: MspCommandCode::MSP_BATTERY_CONFIG.to_primitive(),
1571                direction: FromFlightController,
1572                data: pack_or_empty(Some(config)).unwrap_or_default(),
1573            },
1574            MspRequest::MspBatteryStateRequest => MspPacket {
1575                cmd: MspCommandCode::MSP_BATTERY_STATE.to_primitive(),
1576                direction: ToFlightController,
1577                data: MspPacketData::new(), // empty
1578            },
1579            MspRequest::MspBatteryState(state) => MspPacket {
1580                cmd: MspCommandCode::MSP_BATTERY_STATE.to_primitive(),
1581                direction: FromFlightController,
1582                data: pack_or_empty(Some(state)).unwrap_or_default(),
1583            },
1584            MspRequest::MspAnalogRequest => MspPacket {
1585                cmd: MspCommandCode::MSP_ANALOG.to_primitive(),
1586                direction: ToFlightController,
1587                data: MspPacketData::new(), // empty
1588            },
1589            MspRequest::MspAnalog(analog) => MspPacket {
1590                cmd: MspCommandCode::MSP_ANALOG.to_primitive(),
1591                direction: FromFlightController,
1592                data: pack_or_empty(Some(analog)).unwrap_or_default(),
1593            },
1594            MspRequest::MspVoltageMeterConfigRequest => MspPacket {
1595                cmd: MspCommandCode::MSP_VOLTAGE_METER_CONFIG.to_primitive(),
1596                direction: ToFlightController,
1597                data: MspPacketData::new(),
1598            },
1599            MspRequest::MspVoltageMeterConfig(config) => MspPacket {
1600                cmd: MspCommandCode::MSP_VOLTAGE_METER_CONFIG.to_primitive(),
1601                direction: FromFlightController,
1602                data: pack_or_empty(Some(config)).unwrap_or_default(),
1603            },
1604            MspRequest::MspVoltageMetersRequest => MspPacket {
1605                cmd: MspCommandCode::MSP_VOLTAGE_METERS.to_primitive(),
1606                direction: ToFlightController,
1607                data: MspPacketData::new(), // empty
1608            },
1609            MspRequest::MspVoltageMeter(meter) => MspPacket {
1610                cmd: MspCommandCode::MSP_VOLTAGE_METERS.to_primitive(),
1611                direction: FromFlightController,
1612                data: pack_or_empty(Some(meter)).unwrap_or_default(),
1613            },
1614            MspRequest::MspRc => MspPacket {
1615                cmd: MspCommandCode::MSP_RC.to_primitive(),
1616                direction: ToFlightController,
1617                data: MspPacketData::new(), // empty
1618            },
1619            MspRequest::MspSetRawRc(rc) => MspPacket {
1620                cmd: MspCommandCode::MSP_SET_RAW_RC.to_primitive(),
1621                direction: ToFlightController,
1622                data: MspPacketData::from(rc.pack().unwrap().as_slice()),
1623            },
1624            MspRequest::MspRawImu => MspPacket {
1625                cmd: MspCommandCode::MSP_RAW_IMU.to_primitive(),
1626                direction: ToFlightController,
1627                data: MspPacketData::new(), // empty
1628            },
1629            MspRequest::MspStatus(status) => MspPacket {
1630                cmd: MspCommandCode::MSP_STATUS.to_primitive(),
1631                direction: FromFlightController,
1632                data: status.to_packet_data().unwrap(),
1633            },
1634            MspRequest::MspStatusEx(status) => MspPacket {
1635                cmd: MspCommandCode::MSP_STATUS_EX.to_primitive(),
1636                direction: FromFlightController,
1637                data: status.to_packet_data().unwrap(),
1638            },
1639            MspRequest::MspDisplayPort(displayport) => MspPacket {
1640                cmd: MspCommandCode::MSP_DISPLAYPORT.to_primitive(),
1641                direction: FromFlightController,
1642                data: MspPacketData::from(displayport.as_bytes()),
1643            },
1644            MspRequest::MspSensorRangefinder(data) => MspPacket {
1645                cmd: MspCommandCode::MSP2_SENSOR_RANGEFINDER.to_primitive(),
1646                direction: ToFlightController,
1647                data: pack_or_empty(Some(data)).unwrap_or_default(),
1648            },
1649            MspRequest::MspSensorOpticFlow(data) => MspPacket {
1650                cmd: MspCommandCode::MSP2_SENSOR_OPTIC_FLOW.to_primitive(),
1651                direction: ToFlightController,
1652                data: pack_or_empty(Some(data)).unwrap_or_default(),
1653            },
1654            _ => MspPacket {
1655                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1656                direction: ToFlightController,
1657                data: MspPacketData::new(), // empty
1658            },
1659        }
1660    }
1661}
1662
1663// Gather all the commands in a common enum we can use as a higher level protocol
1664#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1665#[derive(Debug, Clone, Default, Serialize, Deserialize)]
1666pub enum MspResponse {
1667    #[default]
1668    Unknown,
1669    MspApiVersion(MspApiVersion),
1670    MspFlightControllerVariant(MspFlightControllerVariant),
1671    MspStatus(MspStatus),
1672    MspStatusEx(MspStatusEx),
1673    MspBfConfig(MspBfConfig),
1674    MspRawImu(MspRawImu),
1675    MspDataFlashSummaryReply(MspDataFlashSummaryReply),
1676    MspDataFlashReply(MspDataFlashReply),
1677    MspDataFlashRead(MspDataFlashRead),
1678    MspAccTrim(MspAccTrim),
1679    MspIdent(MspIdent),
1680    MspMisc(MspMisc),
1681    MspAttitude(MspAttitude),
1682    MspAltitude(MspAltitude),
1683    MspBatteryConfig(MspBatteryConfig),
1684    MspVoltageMeterConfig(MspVoltageMeterConfig),
1685    MspAnalog(MspAnalog),
1686    MspRssiConfig(MspRssiConfig),
1687    MspVoltageMeter(MspVoltageMeter),
1688    MspCurrentMeter(MspCurrentMeter),
1689    MspBatteryState(MspBatteryState),
1690    MspRcTuning(MspRcTuning),
1691    MspRxConfig(MspRxConfig),
1692    MspRcChannelValue(MspRcChannelValue),
1693    MspRcMappedChannel(MspRcMappedChannel),
1694    MspFeatures(MspFeatures),
1695    MspMotor(MspMotor),
1696    MspMotor3DConfig(MspMotor3DConfig),
1697    MspMotorConfig(MspMotorConfig),
1698    MspRcDeadband(MspRcDeadband),
1699    MspSensorAlignment(MspSensorAlignment),
1700    MspAdvancedConfig(MspAdvancedConfig),
1701    MspFilterConfig(MspFilterConfig),
1702    MspPidAdvanced(MspPidAdvanced),
1703    MspSensorConfig(MspSensorConfig),
1704    MspServos(MspServos),
1705    MspMixerConfig(MspMixerConfig),
1706    MspModeRange(MspModeRange),
1707    MspSetModeRange(MspSetModeRange),
1708    MspOsdConfig(MspOsdConfig),
1709    MspSetGetOsdConfig(MspSetGetOsdConfig),
1710    MspSetOsdLayout(MspSetOsdLayout),
1711    MspSetOsdLayoutItem(MspSetOsdLayoutItem),
1712    MspOsdLayouts(MspOsdLayouts),
1713    MspSerialSetting(MspSerialSetting),
1714    MspSettingInfoRequest(MspSettingInfoRequest),
1715    MspSettingInfo(MspSettingInfo),
1716    MspRc(MspRc),
1717}
1718
1719macro_rules! msp_response_command_map {
1720    ($($variant:ident => $cmd:ident),* $(,)?) => {
1721        fn response_command_code(resp: &MspResponse) -> MspCommandCode {
1722            match resp {
1723                $(MspResponse::$variant(_) => MspCommandCode::$cmd,)*
1724                MspResponse::Unknown => MspCommandCode::MSP_API_VERSION,
1725            }
1726        }
1727    };
1728}
1729
1730macro_rules! msp_response_decode_map {
1731    ($($cmd:ident => $variant:ident : $ty:ty => |$packet:ident| $decode:expr),* $(,)?) => {
1732        fn decode_response(cmd: MspCommandCode, packet: &MspPacket) -> MspResponse {
1733            match cmd {
1734                $(
1735                    MspCommandCode::$cmd => {
1736                        let $packet = packet;
1737                        $decode
1738                            .map(MspResponse::$variant)
1739                            .unwrap_or(MspResponse::Unknown)
1740                    }
1741                )*
1742                _ => MspResponse::Unknown,
1743            }
1744        }
1745    };
1746}
1747
1748msp_response_command_map!(
1749    MspApiVersion => MSP_API_VERSION,
1750    MspFlightControllerVariant => MSP_FC_VARIANT,
1751    MspStatus => MSP_STATUS,
1752    MspStatusEx => MSP_STATUS_EX,
1753    MspBfConfig => MSP_BF_CONFIG,
1754    MspRawImu => MSP_RAW_IMU,
1755    MspDataFlashSummaryReply => MSP_DATAFLASH_SUMMARY,
1756    MspDataFlashReply => MSP_DATAFLASH_READ,
1757    MspDataFlashRead => MSP_DATAFLASH_READ,
1758    MspAccTrim => MSP_ACC_TRIM,
1759    MspIdent => MSP_IDENT,
1760    MspMisc => MSP_MISC,
1761    MspAttitude => MSP_ATTITUDE,
1762    MspAltitude => MSP_ALTITUDE,
1763    MspBatteryConfig => MSP_BATTERY_CONFIG,
1764    MspVoltageMeterConfig => MSP_VOLTAGE_METER_CONFIG,
1765    MspAnalog => MSP_ANALOG,
1766    MspRssiConfig => MSP_RSSI_CONFIG,
1767    MspVoltageMeter => MSP_VOLTAGE_METERS,
1768    MspCurrentMeter => MSP_AMPERAGE_METER_CONFIG,
1769    MspBatteryState => MSP_BATTERY_STATE,
1770    MspRcTuning => MSP_RC_TUNING,
1771    MspRxConfig => MSP_RX_CONFIG,
1772    MspRcChannelValue => MSP_RX_MAP,
1773    MspRcMappedChannel => MSP_SET_RX_MAP,
1774    MspFeatures => MSP_FEATURE,
1775    MspMotor => MSP_MOTOR,
1776    MspMotor3DConfig => MSP_MOTOR_3D_CONFIG,
1777    MspMotorConfig => MSP_MOTOR_CONFIG,
1778    MspRcDeadband => MSP_RC_DEADBAND,
1779    MspSensorAlignment => MSP_BOARD_ALIGNMENT,
1780    MspAdvancedConfig => MSP_ADVANCED_CONFIG,
1781    MspFilterConfig => MSP_FILTER_CONFIG,
1782    MspPidAdvanced => MSP_PID_ADVANCED,
1783    MspSensorConfig => MSP_SENSOR_CONFIG,
1784    MspServos => MSP_SERVO,
1785    MspMixerConfig => MSP_MIXER,
1786    MspModeRange => MSP_MODE_RANGES,
1787    MspSetModeRange => MSP_SET_MODE_RANGE,
1788    MspOsdConfig => MSP_OSD_CONFIG,
1789    MspSetGetOsdConfig => MSP_OSD_CONFIG,
1790    MspSetOsdLayout => MSP_OSD_LAYOUT_CONFIG,
1791    MspSetOsdLayoutItem => MSP2_INAV_OSD_SET_LAYOUT_ITEM,
1792    MspOsdLayouts => MSP2_INAV_OSD_LAYOUTS,
1793    MspSerialSetting => MSP2_SET_SERIAL_CONFIG,
1794    MspSettingInfoRequest => MSP2_COMMON_SETTING,
1795    MspSettingInfo => MSP2_COMMON_SETTING_INFO,
1796    MspRc => MSP_RC,
1797);
1798
1799msp_response_decode_map!(
1800    MSP_API_VERSION => MspApiVersion: MspApiVersion => |packet| packet.decode_as::<MspApiVersion>(),
1801    MSP_FC_VARIANT => MspFlightControllerVariant: MspFlightControllerVariant => |packet| {
1802        packet.decode_as::<MspFlightControllerVariant>()
1803    },
1804    MSP_STATUS => MspStatus: MspStatus => |packet| MspStatus::from_bytes(packet.data.as_slice()),
1805    MSP_STATUS_EX => MspStatusEx: MspStatusEx => |packet| {
1806        MspStatusEx::from_bytes(packet.data.as_slice())
1807    },
1808    MSP_BF_CONFIG => MspBfConfig: MspBfConfig => |packet| packet.decode_as::<MspBfConfig>(),
1809    MSP_RAW_IMU => MspRawImu: MspRawImu => |packet| packet.decode_as::<MspRawImu>(),
1810    MSP_DATAFLASH_SUMMARY => MspDataFlashSummaryReply: MspDataFlashSummaryReply => |packet| {
1811        packet.decode_as::<MspDataFlashSummaryReply>()
1812    },
1813    MSP_DATAFLASH_READ => MspDataFlashReply: MspDataFlashReply => |packet| {
1814        packet.decode_as::<MspDataFlashReply>()
1815    },
1816    MSP_ACC_TRIM => MspAccTrim: MspAccTrim => |packet| packet.decode_as::<MspAccTrim>(),
1817    MSP_IDENT => MspIdent: MspIdent => |packet| packet.decode_as::<MspIdent>(),
1818    MSP_MISC => MspMisc: MspMisc => |packet| packet.decode_as::<MspMisc>(),
1819    MSP_ATTITUDE => MspAttitude: MspAttitude => |packet| packet.decode_as::<MspAttitude>(),
1820    MSP_ALTITUDE => MspAltitude: MspAltitude => |packet| packet.decode_as::<MspAltitude>(),
1821    MSP_BATTERY_CONFIG => MspBatteryConfig: MspBatteryConfig => |packet| {
1822        packet.decode_as::<MspBatteryConfig>()
1823    },
1824    MSP_VOLTAGE_METER_CONFIG => MspVoltageMeterConfig: MspVoltageMeterConfig => |packet| {
1825        packet.decode_as::<MspVoltageMeterConfig>()
1826    },
1827    MSP_ANALOG => MspAnalog: MspAnalog => |packet| packet.decode_as::<MspAnalog>(),
1828    MSP_RSSI_CONFIG => MspRssiConfig: MspRssiConfig => |packet| {
1829        packet.decode_as::<MspRssiConfig>()
1830    },
1831    MSP_VOLTAGE_METERS => MspVoltageMeter: MspVoltageMeter => |packet| {
1832        packet.decode_as::<MspVoltageMeter>()
1833    },
1834    MSP_AMPERAGE_METER_CONFIG => MspCurrentMeter: MspCurrentMeter => |packet| {
1835        packet.decode_as::<MspCurrentMeter>()
1836    },
1837    MSP_BATTERY_STATE => MspBatteryState: MspBatteryState => |packet| {
1838        packet.decode_as::<MspBatteryState>()
1839    },
1840    MSP_RC_TUNING => MspRcTuning: MspRcTuning => |packet| packet.decode_as::<MspRcTuning>(),
1841    MSP_RX_CONFIG => MspRxConfig: MspRxConfig => |packet| packet.decode_as::<MspRxConfig>(),
1842    MSP_RX_MAP => MspRcChannelValue: MspRcChannelValue => |packet| {
1843        packet.decode_as::<MspRcChannelValue>()
1844    },
1845    MSP_SET_RX_MAP => MspRcMappedChannel: MspRcMappedChannel => |packet| {
1846        packet.decode_as::<MspRcMappedChannel>()
1847    },
1848    MSP_FEATURE => MspFeatures: MspFeatures => |packet| packet.decode_as::<MspFeatures>(),
1849    MSP_MOTOR => MspMotor: MspMotor => |packet| packet.decode_as::<MspMotor>(),
1850    MSP_MOTOR_3D_CONFIG => MspMotor3DConfig: MspMotor3DConfig => |packet| {
1851        packet.decode_as::<MspMotor3DConfig>()
1852    },
1853    MSP_MOTOR_CONFIG => MspMotorConfig: MspMotorConfig => |packet| {
1854        packet.decode_as::<MspMotorConfig>()
1855    },
1856    MSP_RC_DEADBAND => MspRcDeadband: MspRcDeadband => |packet| packet.decode_as::<MspRcDeadband>(),
1857    MSP_BOARD_ALIGNMENT => MspSensorAlignment: MspSensorAlignment => |packet| {
1858        packet.decode_as::<MspSensorAlignment>()
1859    },
1860    MSP_ADVANCED_CONFIG => MspAdvancedConfig: MspAdvancedConfig => |packet| {
1861        packet.decode_as::<MspAdvancedConfig>()
1862    },
1863    MSP_FILTER_CONFIG => MspFilterConfig: MspFilterConfig => |packet| {
1864        packet.decode_as::<MspFilterConfig>()
1865    },
1866    MSP_PID_ADVANCED => MspPidAdvanced: MspPidAdvanced => |packet| {
1867        packet.decode_as::<MspPidAdvanced>()
1868    },
1869    MSP_SENSOR_CONFIG => MspSensorConfig: MspSensorConfig => |packet| {
1870        packet.decode_as::<MspSensorConfig>()
1871    },
1872    MSP_SERVO => MspServos: MspServos => |packet| packet.decode_as::<MspServos>(),
1873    MSP_MIXER => MspMixerConfig: MspMixerConfig => |packet| packet.decode_as::<MspMixerConfig>(),
1874    MSP_MODE_RANGES => MspModeRange: MspModeRange => |packet| packet.decode_as::<MspModeRange>(),
1875    MSP_SET_MODE_RANGE => MspSetModeRange: MspSetModeRange => |packet| {
1876        packet.decode_as::<MspSetModeRange>()
1877    },
1878    MSP_OSD_CONFIG => MspOsdConfig: MspOsdConfig => |packet| packet.decode_as::<MspOsdConfig>(),
1879    MSP_OSD_LAYOUT_CONFIG => MspSetOsdLayout: MspSetOsdLayout => |packet| {
1880        packet.decode_as::<MspSetOsdLayout>()
1881    },
1882    MSP2_INAV_OSD_SET_LAYOUT_ITEM => MspSetOsdLayoutItem: MspSetOsdLayoutItem => |packet| {
1883        packet.decode_as::<MspSetOsdLayoutItem>()
1884    },
1885    MSP2_INAV_OSD_LAYOUTS => MspOsdLayouts: MspOsdLayouts => |packet| {
1886        packet.decode_as::<MspOsdLayouts>()
1887    },
1888    MSP2_SET_SERIAL_CONFIG => MspSerialSetting: MspSerialSetting => |packet| {
1889        packet.decode_as::<MspSerialSetting>()
1890    },
1891    MSP2_COMMON_SETTING => MspSettingInfoRequest: MspSettingInfoRequest => |packet| {
1892        packet.decode_as::<MspSettingInfoRequest>()
1893    },
1894    MSP2_COMMON_SETTING_INFO => MspSettingInfo: MspSettingInfo => |packet| {
1895        packet.decode_as::<MspSettingInfo>()
1896    },
1897    MSP_RC => MspRc: MspRc => |packet| packet.decode_as::<MspRc>(),
1898);
1899
1900impl MspResponse {
1901    pub fn command_code(&self) -> MspCommandCode {
1902        // TODO: Not sure about all those mapping recheck them.
1903        response_command_code(self)
1904    }
1905
1906    pub fn to_bytes(&self) -> Result<MspPacketData, PackingError> {
1907        fn pack_into_packet_data<T: PackedStruct>(
1908            value: &T,
1909        ) -> Result<MspPacketData, PackingError> {
1910            let packed = value.pack()?;
1911            Ok(MspPacketData::from(packed.as_bytes_slice()))
1912        }
1913
1914        match self {
1915            MspResponse::MspApiVersion(data) => pack_into_packet_data(data),
1916            MspResponse::MspFlightControllerVariant(data) => pack_into_packet_data(data),
1917            MspResponse::MspStatus(data) => data.to_packet_data(),
1918            MspResponse::MspStatusEx(data) => data.to_packet_data(),
1919            MspResponse::MspBfConfig(data) => pack_into_packet_data(data),
1920            MspResponse::MspRawImu(data) => pack_into_packet_data(data),
1921            MspResponse::MspDataFlashSummaryReply(data) => pack_into_packet_data(data),
1922            MspResponse::MspDataFlashReply(data) => pack_into_packet_data(data),
1923            MspResponse::MspDataFlashRead(data) => pack_into_packet_data(data),
1924            MspResponse::MspAccTrim(data) => pack_into_packet_data(data),
1925            MspResponse::MspIdent(data) => pack_into_packet_data(data),
1926            MspResponse::MspMisc(data) => pack_into_packet_data(data),
1927            MspResponse::MspAttitude(data) => pack_into_packet_data(data),
1928            MspResponse::MspAltitude(data) => pack_into_packet_data(data),
1929            MspResponse::MspBatteryConfig(data) => pack_into_packet_data(data),
1930            MspResponse::MspVoltageMeterConfig(data) => pack_into_packet_data(data),
1931            MspResponse::MspAnalog(data) => pack_into_packet_data(data),
1932            MspResponse::MspRssiConfig(data) => pack_into_packet_data(data),
1933            MspResponse::MspVoltageMeter(data) => pack_into_packet_data(data),
1934            MspResponse::MspCurrentMeter(data) => pack_into_packet_data(data),
1935            MspResponse::MspBatteryState(data) => pack_into_packet_data(data),
1936            MspResponse::MspRcTuning(data) => pack_into_packet_data(data),
1937            MspResponse::MspRxConfig(data) => pack_into_packet_data(data),
1938            MspResponse::MspRcChannelValue(data) => pack_into_packet_data(data),
1939            MspResponse::MspRcMappedChannel(data) => pack_into_packet_data(data),
1940            MspResponse::MspFeatures(data) => pack_into_packet_data(data),
1941            MspResponse::MspMotor(data) => pack_into_packet_data(data),
1942            MspResponse::MspMotor3DConfig(data) => pack_into_packet_data(data),
1943            MspResponse::MspMotorConfig(data) => pack_into_packet_data(data),
1944            MspResponse::MspRcDeadband(data) => pack_into_packet_data(data),
1945            MspResponse::MspSensorAlignment(data) => pack_into_packet_data(data),
1946            MspResponse::MspAdvancedConfig(data) => pack_into_packet_data(data),
1947            MspResponse::MspFilterConfig(data) => pack_into_packet_data(data),
1948            MspResponse::MspPidAdvanced(data) => pack_into_packet_data(data),
1949            MspResponse::MspSensorConfig(data) => pack_into_packet_data(data),
1950            MspResponse::MspServos(data) => pack_into_packet_data(data),
1951            MspResponse::MspMixerConfig(data) => pack_into_packet_data(data),
1952            MspResponse::MspModeRange(data) => pack_into_packet_data(data),
1953            MspResponse::MspSetModeRange(data) => pack_into_packet_data(data),
1954            MspResponse::MspOsdConfig(data) => pack_into_packet_data(data),
1955            MspResponse::MspSetGetOsdConfig(data) => pack_into_packet_data(data),
1956            MspResponse::MspSetOsdLayout(data) => pack_into_packet_data(data),
1957            MspResponse::MspSetOsdLayoutItem(data) => pack_into_packet_data(data),
1958            MspResponse::MspOsdLayouts(data) => pack_into_packet_data(data),
1959            MspResponse::MspSerialSetting(data) => pack_into_packet_data(data),
1960            MspResponse::MspSettingInfoRequest(data) => pack_into_packet_data(data),
1961            MspResponse::MspSettingInfo(data) => pack_into_packet_data(data),
1962            MspResponse::MspRc(data) => pack_into_packet_data(data),
1963            MspResponse::Unknown => Err(PackingError::InvalidValue),
1964        }
1965    }
1966}
1967
1968impl From<MspResponse> for MspPacket {
1969    fn from(command: MspResponse) -> Self {
1970        MspPacket {
1971            cmd: command.command_code().to_primitive(),
1972            direction: FromFlightController,
1973            data: command.to_bytes().unwrap(), // should always be able to serialize a constructed MSPCommand
1974        }
1975    }
1976}
1977impl From<MspPacket> for MspResponse {
1978    fn from(packet: MspPacket) -> Self {
1979        let Some(cmd) = MspCommandCode::from_primitive(packet.cmd) else {
1980            return MspResponse::Unknown;
1981        };
1982        decode_response(cmd, &packet)
1983    }
1984}
1985
1986#[cfg(test)]
1987mod msp_status_tests {
1988    use super::*;
1989
1990    #[test]
1991    fn msp_status_serialization_roundtrip() {
1992        let status = MspStatus {
1993            cycle_time: 1234,
1994            i2c_errors: 5,
1995            sensors: MspStatusSensors {
1996                acc: true,
1997                baro: true,
1998                mag: false,
1999                gps: false,
2000                rangefinder: false,
2001                gyro: true,
2002                optical_flow: false,
2003            },
2004            flight_mode_flags: 0x11223344,
2005            current_pid_profile_index: 2,
2006            average_system_load_percent: 100,
2007            gyro_cycle_time: 250,
2008            extra_flight_mode_flags: vec![0xAA, 0xBB],
2009            arming_disable_flags_count: 29,
2010            arming_disable_flags: 0xDEADBEEF,
2011            config_state_flags: 1,
2012            core_temp_celsius: 42,
2013            control_rate_profile_count: 3,
2014        };
2015
2016        let data = status.to_packet_data().expect("serialize MSP_STATUS");
2017        let expected = vec![
2018            0xD2, 0x04, // cycle_time
2019            0x05, 0x00, // i2c_errors
2020            0x23, 0x00, // sensors
2021            0x44, 0x33, 0x22, 0x11, // flight_mode_flags
2022            0x02, // current_pid_profile_index
2023            0x64, 0x00, // average_system_load_percent
2024            0xFA, 0x00, // gyro_cycle_time
2025            0x02, // extra_flight_mode_flags_len
2026            0xAA, 0xBB, // extra_flight_mode_flags
2027            0x1D, // arming_disable_flags_count
2028            0xEF, 0xBE, 0xAD, 0xDE, // arming_disable_flags
2029            0x01, // config_state_flags
2030            0x2A, 0x00, // core_temp_celsius
2031            0x03, // control_rate_profile_count
2032        ];
2033
2034        assert_eq!(data.as_slice(), expected.as_slice());
2035
2036        let decoded = MspStatus::from_bytes(data.as_slice()).expect("decode MSP_STATUS");
2037        assert_eq!(decoded, status);
2038    }
2039
2040    #[test]
2041    fn msp_status_ex_serialization_roundtrip() {
2042        let status = MspStatusEx {
2043            cycle_time: 321,
2044            i2c_errors: 1,
2045            sensors: MspStatusSensors {
2046                acc: true,
2047                baro: false,
2048                mag: true,
2049                gps: false,
2050                rangefinder: false,
2051                gyro: true,
2052                optical_flow: true,
2053            },
2054            flight_mode_flags: 0xAABBCCDD,
2055            current_pid_profile_index: 1,
2056            average_system_load_percent: 250,
2057            max_profile_count: 3,
2058            current_control_rate_profile_index: 2,
2059            extra_flight_mode_flags: vec![],
2060            arming_disable_flags_count: 29,
2061            arming_disable_flags: 0,
2062            config_state_flags: 0,
2063            core_temp_celsius: 0,
2064            control_rate_profile_count: 3,
2065        };
2066
2067        let data = status.to_packet_data().expect("serialize MSP_STATUS_EX");
2068        let decoded = MspStatusEx::from_bytes(data.as_slice()).expect("decode MSP_STATUS_EX");
2069        assert_eq!(decoded, status);
2070    }
2071}
2072
2073#[cfg(test)]
2074mod tests {
2075    use super::*;
2076    #[test]
2077    fn test_mixer() {
2078        use packed_struct::prelude::*;
2079
2080        let m = MspMixerConfig {
2081            mixer_mode: MixerMode::QuadX,
2082        };
2083        assert_eq!(3, m.mixer_mode.to_primitive());
2084        let r = m.pack().unwrap();
2085        assert_eq!(3, r.as_slice()[0]);
2086    }
2087
2088    #[test]
2089    #[cfg(feature = "bincode")]
2090    fn test_command_enum_with_bincode() {
2091        let command = MspResponse::MspApiVersion(MspApiVersion {
2092            protocol_version: 1,
2093            api_version_major: 2,
2094            api_version_minor: 3,
2095        });
2096
2097        let encoded = bincode::encode_to_vec(&command, bincode::config::standard()).unwrap();
2098        let decoded: MspResponse =
2099            bincode::decode_from_slice(&encoded, bincode::config::standard())
2100                .unwrap()
2101                .0;
2102
2103        match (command, decoded) {
2104            (MspResponse::MspApiVersion(c1), MspResponse::MspApiVersion(c2)) => {
2105                assert_eq!(c1.protocol_version, c2.protocol_version);
2106                assert_eq!(c1.api_version_major, c2.api_version_major);
2107                assert_eq!(c1.api_version_minor, c2.api_version_minor);
2108            }
2109            _ => panic!("Decoded command does not match the original command"),
2110        }
2111    }
2112}