cu_msp_lib/
structs.rs

1//! MSP structures
2
3use packed_struct::derive::{PackedStruct, PrimitiveEnum};
4use serde::{Deserialize, Serialize};
5
6use crate::commands::MspCommandCode;
7use crate::MspPacketDirection::{FromFlightController, ToFlightController};
8use crate::{MspPacket, MspPacketData};
9
10// std implementation
11#[cfg(feature = "std")]
12mod std_impl {
13    pub use std::{string::String, vec::Vec};
14}
15
16// no-std implementation
17#[cfg(not(feature = "std"))]
18mod no_std_impl {
19    pub use alloc::{borrow::ToOwned, string::String, vec::Vec};
20}
21
22#[cfg(not(feature = "std"))]
23use no_std_impl::*;
24#[cfg(feature = "std")]
25use std_impl::*;
26
27#[cfg(feature = "bincode")]
28use bincode::{Decode, Encode};
29use packed_struct::types::bits::ByteArray;
30use packed_struct::{PackedStruct, PackingError, PrimitiveEnum};
31use smallvec::SmallVec;
32
33#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
34#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
35pub struct MspApiVersion {
36    pub protocol_version: u8,
37    pub api_version_major: u8,
38    pub api_version_minor: u8,
39}
40
41#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
42#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
43pub struct MspFlightControllerVariant {
44    pub identifier: [u8; 4],
45}
46
47#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
48#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
49pub struct MspFlightControllerVersion {
50    pub major: u8,
51    pub minor: u8,
52    pub patch: u8,
53}
54
55#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
56#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
57#[packed_struct(endian = "lsb")]
58pub struct MspBoardInfo {
59    pub board_id: [u8; 4],
60    pub hardware_revision: u16,
61    pub fc_type: u8,
62}
63
64#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
65#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
66pub struct MspBuildInfo {
67    pub date_str: [u8; 11],
68    pub time_str: [u8; 8],
69    pub git_str: [u8; 7],
70}
71
72#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
73#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
74pub struct MspUniqueId {
75    pub uid: [u8; 12],
76}
77
78#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
79#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
80#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
81pub struct MspAvailableSensors {
82    #[packed_field(bits = "2")]
83    pub sonar: bool,
84    #[packed_field(bits = "4")]
85    pub gps: bool,
86    #[packed_field(bits = "5")]
87    pub mag: bool,
88    #[packed_field(bits = "6")]
89    pub baro: bool,
90    #[packed_field(bits = "7")]
91    pub acc: bool,
92}
93
94#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
95#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
96#[packed_struct(endian = "lsb")]
97pub struct MspStatus {
98    pub cycle_time: u16,
99    pub i2c_errors: u16,
100    #[packed_field(size_bits = "8")]
101    pub sensors: MspAvailableSensors,
102    pub null1: u8,
103    pub flight_mode: u32,
104    pub profile: u8,
105    pub system_load: u16,
106}
107
108#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
109#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
110#[packed_struct(endian = "lsb")]
111pub struct MspStatusEx {
112    pub cycle_time: u16,
113    pub i2c_errors: u16,
114    #[packed_field(size_bits = "8")]
115    pub sensors: MspAvailableSensors,
116    pub null1: u8,
117    pub flight_mode: u32,
118    pub current_pid_profile_index: u8,
119    pub average_system_load_percent: u16,
120    pub max_profile_count: u8,
121    pub current_control_rate_profile_index: u8,
122}
123
124#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
125#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
126#[packed_struct(endian = "lsb")]
127pub struct MspBfConfig {
128    pub mixer_configuration: u8,
129    pub features: u32,
130    pub serial_rx_provider: u8,
131    pub board_align_roll: i16,
132    pub board_align_pitch: i16,
133    pub board_align_yaw: i16,
134    pub current_scale: i16,
135    pub current_offset: i16,
136}
137
138#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
139#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
140#[packed_struct(endian = "lsb")]
141pub struct MspRawImu {
142    pub acc_x: i16,
143    pub acc_y: i16,
144    pub acc_z: i16,
145    pub gyro_x: i16,
146    pub gyro_y: i16,
147    pub gyro_z: i16,
148    pub mag_x: i16,
149    pub mag_y: i16,
150    pub mag_z: i16,
151}
152
153#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
154#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
155#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
156pub struct MspDataFlashSummaryReply {
157    #[packed_field(bits = "6")]
158    pub supported: bool,
159    #[packed_field(bits = "7")]
160    pub ready: bool,
161    pub sectors: u32,
162    pub total_size_bytes: u32,
163    pub used_size_bytes: u32,
164}
165
166#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
167#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
168#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
169pub struct MspDataFlashReply {
170    pub read_address: u32,
171    // pub payload: Vec<u8>, // TODO: packed_struct should support dynamic size too the end
172}
173
174#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
175#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
176#[packed_struct(bytes = "6", endian = "lsb", bit_numbering = "msb0")]
177pub struct MspDataFlashRead {
178    pub read_address: u32,
179    pub read_length: u16,
180}
181
182#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
183#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
184#[packed_struct(endian = "lsb")]
185pub struct MspAccTrim {
186    pub pitch: u16,
187    pub roll: u16,
188}
189
190#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
191#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
192#[packed_struct(endian = "lsb")]
193pub struct MspIdent {
194    pub version: u8,
195    pub mixer_mode: u8,
196    pub protocol_version: u8,
197    pub capability: u32,
198}
199
200#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
201#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
202#[packed_struct(endian = "lsb")]
203pub struct MspMisc {
204    pub rx_mid_rc: u16,
205    pub min_throttle: u16,
206    pub max_throttle: u16,
207    pub min_command: u16,
208    pub failsafe_throttle: u16,
209
210    pub gps_type: u8,
211    pub gps_baudrate: u8,
212    pub gps_sbas_mode: u8,
213
214    pub current_meter_output: u8,
215    pub rssi_channel: u8,
216    pub null1: u8,
217
218    pub compass_mag_declination: u16,
219}
220
221#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
222#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
223#[packed_struct(endian = "lsb")]
224pub struct MspAttitude {
225    pub roll: i16,
226    pub pitch: i16,
227    pub yaw: i16,
228}
229
230#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
231#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
232#[packed_struct(endian = "lsb")]
233pub struct MspAltitude {
234    /// [centimeters]
235    pub altitude: i32,
236    /// variometer [cm/s]
237    pub vario: i16,
238}
239
240#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
241#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
242#[packed_struct(endian = "lsb")]
243pub struct MspBatteryConfig {
244    pub vbat_min_cell_voltage: u8,
245    pub vbat_max_cell_voltage: u8,
246    pub vbat_warning_cell_voltage: u8,
247    pub battery_capacity: u16,
248    pub voltage_meter_source: u8,
249    pub current_meter_source: u8,
250}
251
252#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
253#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
254#[packed_struct(endian = "lsb")]
255pub struct MspAnalog {
256    pub battery_voltage: u8,
257    pub mah_drawn: u16,
258    pub rssi: u16,
259    /// Current in 0.01A steps, range is -320A to 320A
260    pub amperage: i16,
261}
262
263#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
264#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
265#[packed_struct(endian = "lsb")]
266pub struct MspRssiConfig {
267    pub rssi_channel: u8,
268}
269
270#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
271#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
272pub struct MspVoltageMeter {
273    pub id: u8,
274    pub value: u8,
275}
276
277#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
278#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
279#[packed_struct(endian = "lsb")]
280pub struct MspCurrentMeter {
281    pub id: u8,
282    pub mah_drawn: u16,
283    /// In 0.001A steps (mA)
284    pub amperage: u16,
285}
286
287#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
288#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
289#[packed_struct(endian = "lsb")]
290pub struct MspBatteryState {
291    pub battery_cell_count: u8,
292    /// mAh
293    pub battery_capacity: u16,
294
295    pub battery_voltage: u8,
296    pub mah_drawn: u16,
297    /// 0.01A
298    pub amperage: i16,
299
300    pub alerts: u8,
301}
302
303impl MspBatteryState {
304    pub fn cell_voltage(&self) -> f32 {
305        self.battery_voltage as f32 / (10 * self.battery_cell_count) as f32
306    }
307}
308
309#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
310#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
311#[packed_struct(endian = "lsb")]
312pub struct MspRcTuning {
313    pub rc_rate8: u8,
314    pub rc_expo8: u8,
315
316    pub rate_roll: u8,
317    pub rate_pitch: u8,
318    pub rate_yaw: u8,
319
320    pub dyn_thr_pid: u8,
321    pub thr_mid8: u8,
322    pub thr_expo8: u8,
323    pub tpa_breakpoint: u16,
324    pub rc_yaw_expo8: u8,
325    pub rc_yaw_rate8: u8,
326}
327
328#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
329#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
330#[packed_struct(endian = "lsb")]
331pub struct MspRxConfig {
332    pub serialrx_provider: u8,
333    pub maxcheck: u16,
334    pub midrc: u16,
335    pub mincheck: u16,
336    pub spektrum_sat_bind: u8,
337    pub rx_min_usec: u16,
338    pub rx_max_usec: u16,
339    pub rc_interpolation: u8,
340    pub rc_interpolation_interval: u8,
341    pub air_mode_activate_threshold: u16,
342    pub rx_spi_protocol: u8,
343    pub rx_spi_id: u32,
344    pub rx_spi_rf_channel_count: u8,
345    pub fpv_cam_angle_degrees: u8,
346}
347
348#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
349#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
350#[packed_struct(endian = "lsb")]
351pub struct MspRcChannelValue {
352    pub value: u16,
353}
354
355#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
356#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
357pub enum MspRcChannel {
358    /// Ailerons
359    #[default]
360    Roll = 0,
361    /// Elevators
362    Pitch = 1,
363    /// Rudder
364    Yaw = 2,
365    Throttle = 3,
366    Aux1 = 4,
367    Aux2 = 5,
368    Aux3 = 6,
369    Aux4 = 7,
370    Aux5 = 8,
371    Aux6 = 9,
372    Aux7 = 10,
373    Aux8 = 11,
374    Aux9 = 12,
375    Aux10 = 13,
376    Aux11 = 14,
377    Aux12 = 15,
378    Aux13 = 16,
379    Aux14 = 17,
380    Aux15 = 18,
381    Aux16 = 19,
382}
383
384#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
385#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
386pub struct MspRcMappedChannel {
387    #[packed_field(size_bits = "8", ty = "enum")]
388    pub channel: MspRcChannel,
389}
390
391#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
392#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
393pub struct MspFeatures {
394    pub features: [bool; 32],
395}
396
397#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
398#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
399#[packed_struct(endian = "lsb")]
400pub struct MspMotor {
401    pub motors: [u16; 8],
402}
403
404#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
405#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
406#[packed_struct(endian = "lsb")]
407pub struct MspMotor3DConfig {
408    pub deadband_3d_low: u16,
409    pub deadband_3d_high: u16,
410    pub neutral_3d: u16,
411}
412
413#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
414#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
415#[packed_struct(endian = "lsb")]
416pub struct MspMotorConfig {
417    pub min_throttle: u16,
418    pub max_throttle: u16,
419    pub min_command: u16,
420}
421
422#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
423#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
424#[packed_struct(endian = "lsb")]
425pub struct MspRcDeadband {
426    pub deadband: u8,
427    pub yaw_deadband: u8,
428    pub alt_hold_deadband: u8,
429    pub deadband_3d_throttle: u16,
430}
431
432#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
433#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
434#[packed_struct(endian = "lsb")]
435pub struct MspSensorAlignment {
436    pub gyro_alignment: u8,
437    pub acc_alignment: u8,
438    pub mag_alignment: u8,
439}
440
441#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
442#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
443#[packed_struct(endian = "lsb")]
444pub struct MspAdvancedConfig {
445    pub gyro_sync_denom: u8,
446    pub pid_process_denom: u8,
447    pub use_unsynced_pwm: u8,
448    pub motor_pwm_protocol: u8,
449    pub motor_pwm_rate: u16,
450    pub digital_idle_offset_percent: u16,
451    pub gyro_use_32khz: u8,
452    pub motor_pwm_inversion: u8,
453}
454
455#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
456#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
457#[packed_struct(endian = "lsb")]
458pub struct MspFilterConfig {
459    pub gyro_soft_lpf_hz: u8,
460    pub dterm_lpf_hz: u16,
461    pub yaw_lpf_hz: u16,
462    pub gyro_soft_notch_hz_1: u16,
463    pub gyro_soft_notch_cutoff_1: u16,
464    pub dterm_notch_hz: u16,
465    pub dterm_notch_cutoff: u16,
466    pub gyro_soft_notch_hz_2: u16,
467    pub gyro_soft_notch_cutoff_2: u16,
468}
469
470#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
471#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
472#[packed_struct(endian = "lsb")]
473pub struct MspPidAdvanced {
474    pub _r1: u16,
475    pub _r2: u16,
476    pub _r3: u16,
477    pub _r4: u8,
478    pub vbat_pid_compensation: u8,
479    pub setpoint_relax_ratio: u8,
480    pub dterm_setpoint_weight: u8,
481    pub _r5: u8,
482    pub _r6: u8,
483    pub _r7: u8,
484    pub rate_accel_limit: u16,
485    pub yaw_rate_accel_limit: u16,
486    pub level_angle_limit: u8,
487    pub level_sensitivity: u8,
488}
489
490#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
491#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
492#[packed_struct(endian = "lsb")]
493pub struct MspSensorConfig {
494    pub acc_hardware: u8,
495    pub baro_hardware: u8,
496    pub mag_hardware: u8,
497}
498
499#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
500#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
501#[packed_struct(endian = "lsb")]
502pub struct MspServos {
503    pub servos: [u16; 8],
504}
505
506#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
507#[derive(PackedStruct, Debug, Copy, Clone, Default)]
508#[packed_struct(bytes = "14", endian = "lsb", bit_numbering = "msb0")]
509pub struct MspServoConfig {
510    pub min: u16,
511    pub max: u16,
512    pub middle: u16,
513    pub rate: i8,
514    pub unused1: u8,
515    pub unused2: u8,
516    pub forward_from_channel: u8, // Deprecated, set to 255 for backward compatibility
517    pub reverse_input: u32, // Deprecated, Input reversing is not required since it can be done on mixer level
518}
519
520#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
521#[derive(PackedStruct, Debug, Copy, Clone, Default)]
522#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
523pub struct MspSetServoConfig {
524    pub index: u8,
525    #[packed_field(size_bytes = "14")]
526    pub servo_config: MspServoConfig,
527}
528
529#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
530#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
531#[packed_struct(endian = "lsb")]
532pub struct MspMixerConfig {
533    #[packed_field(size_bits = "8", ty = "enum")]
534    pub mixer_mode: MixerMode,
535}
536
537#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
538#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
539#[packed_struct(bytes = "4", endian = "lsb", bit_numbering = "msb0")]
540pub struct MspModeRange {
541    pub box_id: u8,
542    #[packed_field(size_bits = "8", ty = "enum")]
543    pub aux_channel_index: MspRcChannel,
544    pub start_step: u8,
545    pub end_step: u8,
546}
547
548#[cfg_attr(feature = "bincode", derive(Decode, Encode, Default))]
549#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)]
550#[packed_struct(bytes = "5", endian = "lsb", bit_numbering = "msb0")]
551pub struct MspSetModeRange {
552    pub index: u8,
553    #[packed_field(size_bytes = "4")]
554    pub mode_range: MspModeRange,
555}
556
557#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
558#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
559pub enum MixerMode {
560    Tri = 1,
561    QuadPlus = 2,
562    #[default]
563    QuadX = 3,
564    Bicopter = 4,
565    Gimbal = 5,
566    Y6 = 6,
567    Hex6 = 7,
568    FlyingWing = 8,
569    Y4 = 9,
570    Hex6X = 10,
571    OctoX8 = 11,
572}
573
574#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
575#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
576#[packed_struct(bytes = "8", endian = "lsb", bit_numbering = "msb0")]
577pub struct MspMotorMixer {
578    pub throttle: u16,
579    pub roll: u16,
580    pub pitch: u16,
581    pub yaw: u16,
582}
583
584#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
585#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
586#[packed_struct(bytes = "9", endian = "lsb", bit_numbering = "msb0")]
587pub struct MspSetMotorMixer {
588    pub index: u8,
589    #[packed_field(size_bytes = "8")]
590    pub motor_mixer: MspMotorMixer,
591}
592
593#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
594#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
595#[packed_struct(bytes = "13", endian = "lsb", bit_numbering = "msb0")]
596pub struct MspOsdConfig {
597    pub video_system: u8,
598    pub units: u8,
599    pub rssi_alarm: u8,
600    pub capacity_warning: u16,
601    pub time_alarm: u16,
602    pub alt_alarm: u16,
603    pub dist_alarm: u16,
604    pub neg_alt_alarm: u16,
605}
606
607#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
608#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
609#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
610pub struct MspSetGetOsdConfig {
611    pub item_index: u8,
612    #[packed_field(size_bytes = "13")]
613    pub config: MspOsdConfig,
614}
615
616#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
617#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
618#[packed_struct(bytes = "2", endian = "lsb", bit_numbering = "msb0")]
619pub struct MspOsdItemPosition {
620    pub col: u8,
621    pub row: u8,
622}
623
624#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
625#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
626#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
627pub struct MspSetOsdLayout {
628    pub item_index: u8,
629    #[packed_field(size_bytes = "2")]
630    pub item: MspOsdItemPosition,
631}
632
633// inav msp layout item
634#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
635#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
636#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
637pub struct MspSetOsdLayoutItem {
638    pub layout_index: u8,
639    #[packed_field(size_bytes = "3")]
640    pub item: MspSetOsdLayout,
641}
642
643#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
644#[derive(Debug, Serialize, Deserialize, Clone, Default)]
645pub struct MspOsdSettings {
646    pub osd_support: u8,
647    pub config: MspOsdConfig,
648    pub item_positions: Vec<MspOsdItemPosition>,
649}
650
651#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
652#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
653#[packed_struct(bytes = "2", endian = "lsb", bit_numbering = "msb0")]
654pub struct MspOsdLayouts {
655    pub layout_count: u8,
656    pub item_count: u8,
657}
658
659#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
660#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
661pub enum SerialIdentifier {
662    #[default]
663    None = 255,
664    USART1 = 0,
665    USART2 = 1,
666    USART3 = 2,
667    USART4 = 3,
668    USART5 = 4,
669    USART6 = 5,
670    USART7 = 6,
671    USART8 = 7,
672    UsbVcp = 20,
673    SoftSerial1 = 30,
674    SoftSerial2 = 31,
675}
676
677impl TryFrom<u8> for SerialIdentifier {
678    type Error = &'static str;
679
680    fn try_from(value: u8) -> Result<Self, Self::Error> {
681        let serial = match value {
682            255 => SerialIdentifier::None,
683            0 => SerialIdentifier::USART1,
684            1 => SerialIdentifier::USART2,
685            2 => SerialIdentifier::USART3,
686            3 => SerialIdentifier::USART4,
687            4 => SerialIdentifier::USART5,
688            5 => SerialIdentifier::USART6,
689            6 => SerialIdentifier::USART7,
690            7 => SerialIdentifier::USART8,
691            20 => SerialIdentifier::UsbVcp,
692            30 => SerialIdentifier::SoftSerial1,
693            31 => SerialIdentifier::SoftSerial2,
694            _ => return Err("Serial identifier not found"),
695        };
696
697        Ok(serial)
698    }
699}
700
701#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
702#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
703pub enum Baudrate {
704    #[default]
705    BaudAuto = 0,
706    Baud1200 = 1,
707    Baud2400 = 2,
708    Baud4800 = 3,
709    Baud9600 = 4,
710    Baud19200 = 5,
711    Baud38400 = 6,
712    Baud57600 = 7,
713    Baud115200 = 8,
714    Baud230400 = 9,
715    Baud250000 = 10,
716    Baud460800 = 11,
717    Baud921600 = 12,
718    Baud1000000 = 13,
719    Baud1500000 = 14,
720    Baud2000000 = 15,
721    Baud2470000 = 16,
722}
723
724impl TryFrom<&str> for Baudrate {
725    type Error = &'static str;
726
727    fn try_from(value: &str) -> Result<Self, Self::Error> {
728        let baudrate = match value {
729            "0" => Baudrate::BaudAuto,
730            "1200" => Baudrate::Baud1200,
731            "2400" => Baudrate::Baud2400,
732            "4800" => Baudrate::Baud4800,
733            "9600" => Baudrate::Baud9600,
734            "19200" => Baudrate::Baud19200,
735            "38400" => Baudrate::Baud38400,
736            "57600" => Baudrate::Baud57600,
737            "115200" => Baudrate::Baud115200,
738            "230400" => Baudrate::Baud230400,
739            "250000" => Baudrate::Baud250000,
740            "460800" => Baudrate::Baud460800,
741            "921600" => Baudrate::Baud921600,
742            "1000000" => Baudrate::Baud1000000,
743            "1500000" => Baudrate::Baud1500000,
744            "2000000" => Baudrate::Baud2000000,
745            "2470000" => Baudrate::Baud2470000,
746            _ => return Err("Baudrate identifier not found"),
747        };
748
749        Ok(baudrate)
750    }
751}
752
753impl From<Baudrate> for String {
754    fn from(value: Baudrate) -> Self {
755        match value {
756            Baudrate::BaudAuto => "0",
757            Baudrate::Baud1200 => "1200",
758            Baudrate::Baud2400 => "2400",
759            Baudrate::Baud4800 => "4800",
760            Baudrate::Baud9600 => "9600",
761            Baudrate::Baud19200 => "19200",
762            Baudrate::Baud38400 => "38400",
763            Baudrate::Baud57600 => "57600",
764            Baudrate::Baud115200 => "115200",
765            Baudrate::Baud230400 => "230400",
766            Baudrate::Baud250000 => "250000",
767            Baudrate::Baud460800 => "460800",
768            Baudrate::Baud921600 => "921600",
769            Baudrate::Baud1000000 => "1000000",
770            Baudrate::Baud1500000 => "1500000",
771            Baudrate::Baud2000000 => "2000000",
772            Baudrate::Baud2470000 => "2470000",
773        }
774        .to_owned()
775    }
776}
777
778#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
779#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
780#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
781pub struct MspSerialSetting {
782    #[packed_field(size_bits = "8", ty = "enum")]
783    pub identifier: SerialIdentifier,
784    pub function_mask: u32,
785    #[packed_field(size_bits = "8", ty = "enum")]
786    pub msp_baudrate_index: Baudrate,
787    #[packed_field(size_bits = "8", ty = "enum")]
788    pub gps_baudrate_index: Baudrate,
789    #[packed_field(size_bits = "8", ty = "enum")]
790    pub telemetry_baudrate_index: Baudrate,
791    #[packed_field(size_bits = "8", ty = "enum")]
792    pub peripheral_baudrate_index: Baudrate,
793}
794
795#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
796#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
797#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
798pub struct MspSetServoMixRule {
799    pub index: u8,
800    #[packed_field(size_bytes = "8")]
801    pub servo_rule: MspServoMixRule,
802}
803
804#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
805#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
806#[packed_struct(bytes = "8", endian = "lsb", bit_numbering = "msb0")]
807pub struct MspServoMixRule {
808    pub target_channel: u8,
809    pub input_source: u8,
810    pub rate: u16,
811    pub speed: u8,
812    pub min: u8,
813    pub max: u8,
814    pub box_id: u8,
815}
816
817#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
818#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
819#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")]
820pub struct MspSetServoMixer {
821    pub index: u8,
822    #[packed_field(size_bytes = "6")]
823    pub servo_rule: MspServoMixer,
824}
825
826#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
827#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
828#[packed_struct(bytes = "6", endian = "lsb", bit_numbering = "msb0")]
829pub struct MspServoMixer {
830    pub target_channel: u8,
831    pub input_source: u8,
832    pub rate: i16,
833    pub speed: u8,
834    pub condition_id: i8,
835}
836
837#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
838#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
839#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
840pub struct MspRxMap {
841    pub map: [u8; 4], // MAX_MAPPABLE_RX_INPUTS
842}
843
844#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
845#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
846#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
847pub struct MspSettingGroup {
848    pub group_id: u16,
849    pub start_id: u16,
850    pub end_id: u16,
851}
852
853#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
854#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
855#[packed_struct(endian = "lsb", bit_numbering = "msb0")]
856pub struct MspSettingInfoRequest {
857    pub null: u8,
858    pub id: u16,
859}
860
861#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
862#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
863pub enum SettingMode {
864    #[default]
865    ModeDirect = 0,
866    ModeLookup = 0x40,
867}
868
869#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
870#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq, Default)]
871pub enum SettingType {
872    #[default]
873    VarUint8 = 0,
874    VarInt8,
875    VarUint16,
876    VarInt16,
877    VarUint32,
878    VarInt32,
879    VarFloat,
880    VarString,
881}
882
883#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
884#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)]
885#[packed_struct(bytes = "15", endian = "lsb", bit_numbering = "msb0")]
886pub struct MspSettingInfo {
887    // pub name: [u8; ?], null terminated strings
888
889    // Parameter Group ID
890    pub group_id: u16,
891
892    // Type, section and mode
893    #[packed_field(size_bits = "8", ty = "enum")]
894    pub setting_type: SettingType,
895    pub setting_section: u8,
896    #[packed_field(size_bits = "8", ty = "enum")]
897    pub setting_mode: SettingMode,
898
899    pub min: u32,
900    pub max: u32,
901
902    // Absolute setting index
903    pub absolute_index: u16,
904
905    // If the setting is profile based, send the current one
906    // and the count, both as uint8_t. For MASTER_VALUE, we
907    // send two zeroes, so the MSP client can assume there
908    pub profile_id: u8,
909    pub profile_count: u8,
910    // if setting uses enum values, it will be written here
911    // pub enum_names: [String; ?] // TODO: packed_struct should support null terminated string parsing
912    // pub value: [u8; ?]
913}
914
915#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
916#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)]
917#[packed_struct(endian = "lsb")]
918pub struct MspRc {
919    pub channels: [u16; 16], // 16 RC channels
920}
921
922impl Default for MspRc {
923    fn default() -> Self {
924        Self::new()
925    }
926}
927
928impl MspRc {
929    pub fn new() -> Self {
930        MspRc { channels: [0; 16] }
931    }
932
933    pub fn set_roll(&mut self, value: u16) {
934        self.channels[0] = value;
935    }
936
937    pub fn set_pitch(&mut self, value: u16) {
938        self.channels[1] = value;
939    }
940
941    pub fn set_throttle(&mut self, value: u16) {
942        self.channels[2] = value;
943    }
944
945    pub fn set_yaw(&mut self, value: u16) {
946        self.channels[3] = value;
947    }
948
949    pub fn set_aux1(&mut self, value: u16) {
950        self.channels[4] = value;
951    }
952    pub fn set_aux2(&mut self, value: u16) {
953        self.channels[5] = value;
954    }
955    pub fn set_aux3(&mut self, value: u16) {
956        self.channels[6] = value;
957    }
958    pub fn set_aux4(&mut self, value: u16) {
959        self.channels[7] = value;
960    }
961}
962
963// Gather all the commands in a common enum we can use as a higher level protocol
964#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
965#[derive(Debug, Clone, Default, Serialize, Deserialize)]
966pub enum MspRequest {
967    #[default]
968    Unknown,
969    MspBatteryState,
970    MspRc,
971    MspSetRawRc(MspRc),
972    MspRawImu,
973}
974
975impl MspRequest {
976    pub fn command_code(&self) -> MspCommandCode {
977        match self {
978            MspRequest::MspBatteryState => MspCommandCode::MSP_BATTERY_STATE,
979            MspRequest::MspRc => MspCommandCode::MSP_RC,
980            MspRequest::MspSetRawRc(_) => MspCommandCode::MSP_SET_RAW_RC,
981            MspRequest::MspRawImu => MspCommandCode::MSP_RAW_IMU,
982            _ => MspCommandCode::MSP_API_VERSION,
983        }
984    }
985}
986
987impl From<MspRequest> for MspPacket {
988    fn from(request: MspRequest) -> Self {
989        match request {
990            MspRequest::MspBatteryState => MspPacket {
991                cmd: MspCommandCode::MSP_BATTERY_STATE.to_primitive(),
992                direction: ToFlightController,
993                data: MspPacketData::new(), // empty
994            },
995            MspRequest::MspRc => MspPacket {
996                cmd: MspCommandCode::MSP_RC.to_primitive(),
997                direction: ToFlightController,
998                data: MspPacketData::new(), // empty
999            },
1000            MspRequest::MspSetRawRc(rc) => {
1001                let data = rc.pack().unwrap();
1002                MspPacket {
1003                    cmd: MspCommandCode::MSP_SET_RAW_RC.to_primitive(),
1004                    direction: ToFlightController,
1005                    data: MspPacketData(SmallVec::from_slice(data.as_slice())),
1006                }
1007            }
1008            MspRequest::MspRawImu => MspPacket {
1009                cmd: MspCommandCode::MSP_RAW_IMU.to_primitive(),
1010                direction: ToFlightController,
1011                data: MspPacketData::new(), // empty
1012            },
1013            _ => MspPacket {
1014                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1015                direction: ToFlightController,
1016                data: MspPacketData::new(), // empty
1017            },
1018        }
1019    }
1020}
1021
1022impl From<&MspRequest> for MspPacket {
1023    fn from(request: &MspRequest) -> Self {
1024        match request {
1025            MspRequest::MspBatteryState => MspPacket {
1026                cmd: MspCommandCode::MSP_BATTERY_STATE.to_primitive(),
1027                direction: ToFlightController,
1028                data: MspPacketData::new(), // empty
1029            },
1030            MspRequest::MspRc => MspPacket {
1031                cmd: MspCommandCode::MSP_RC.to_primitive(),
1032                direction: ToFlightController,
1033                data: MspPacketData::new(), // empty
1034            },
1035            MspRequest::MspSetRawRc(rc) => MspPacket {
1036                cmd: MspCommandCode::MSP_SET_RAW_RC.to_primitive(),
1037                direction: ToFlightController,
1038                data: MspPacketData::from(rc.pack().unwrap().as_slice()),
1039            },
1040            MspRequest::MspRawImu => MspPacket {
1041                cmd: MspCommandCode::MSP_RAW_IMU.to_primitive(),
1042                direction: ToFlightController,
1043                data: MspPacketData::new(), // empty
1044            },
1045            _ => MspPacket {
1046                cmd: MspCommandCode::MSP_API_VERSION.to_primitive(),
1047                direction: ToFlightController,
1048                data: MspPacketData::new(), // empty
1049            },
1050        }
1051    }
1052}
1053
1054// Gather all the commands in a common enum we can use as a higher level protocol
1055#[cfg_attr(feature = "bincode", derive(Decode, Encode))]
1056#[derive(Debug, Clone, Default, Serialize, Deserialize)]
1057pub enum MspResponse {
1058    #[default]
1059    Unknown,
1060    MspApiVersion(MspApiVersion),
1061    MspFlightControllerVariant(MspFlightControllerVariant),
1062    MspStatus(MspStatus),
1063    MspStatusEx(MspStatusEx),
1064    MspBfConfig(MspBfConfig),
1065    MspRawImu(MspRawImu),
1066    MspDataFlashSummaryReply(MspDataFlashSummaryReply),
1067    MspDataFlashReply(MspDataFlashReply),
1068    MspDataFlashRead(MspDataFlashRead),
1069    MspAccTrim(MspAccTrim),
1070    MspIdent(MspIdent),
1071    MspMisc(MspMisc),
1072    MspAttitude(MspAttitude),
1073    MspAltitude(MspAltitude),
1074    MspBatteryConfig(MspBatteryConfig),
1075    MspAnalog(MspAnalog),
1076    MspRssiConfig(MspRssiConfig),
1077    MspVoltageMeter(MspVoltageMeter),
1078    MspCurrentMeter(MspCurrentMeter),
1079    MspBatteryState(MspBatteryState),
1080    MspRcTuning(MspRcTuning),
1081    MspRxConfig(MspRxConfig),
1082    MspRcChannelValue(MspRcChannelValue),
1083    MspRcMappedChannel(MspRcMappedChannel),
1084    MspFeatures(MspFeatures),
1085    MspMotor(MspMotor),
1086    MspMotor3DConfig(MspMotor3DConfig),
1087    MspMotorConfig(MspMotorConfig),
1088    MspRcDeadband(MspRcDeadband),
1089    MspSensorAlignment(MspSensorAlignment),
1090    MspAdvancedConfig(MspAdvancedConfig),
1091    MspFilterConfig(MspFilterConfig),
1092    MspPidAdvanced(MspPidAdvanced),
1093    MspSensorConfig(MspSensorConfig),
1094    MspServos(MspServos),
1095    MspMixerConfig(MspMixerConfig),
1096    MspModeRange(MspModeRange),
1097    MspSetModeRange(MspSetModeRange),
1098    MspOsdConfig(MspOsdConfig),
1099    MspSetGetOsdConfig(MspSetGetOsdConfig),
1100    MspSetOsdLayout(MspSetOsdLayout),
1101    MspSetOsdLayoutItem(MspSetOsdLayoutItem),
1102    MspOsdLayouts(MspOsdLayouts),
1103    MspSerialSetting(MspSerialSetting),
1104    MspSettingInfoRequest(MspSettingInfoRequest),
1105    MspSettingInfo(MspSettingInfo),
1106    MspRc(MspRc),
1107}
1108
1109impl MspResponse {
1110    pub fn command_code(&self) -> MspCommandCode {
1111        // TODO: Not sure about all those mapping recheck them.
1112        match self {
1113            MspResponse::MspApiVersion(_) => MspCommandCode::MSP_API_VERSION,
1114            MspResponse::MspFlightControllerVariant(_) => MspCommandCode::MSP_FC_VARIANT,
1115            MspResponse::MspStatus(_) => MspCommandCode::MSP_STATUS,
1116            MspResponse::MspStatusEx(_) => MspCommandCode::MSP_STATUS_EX,
1117            MspResponse::MspBfConfig(_) => MspCommandCode::MSP_BF_CONFIG,
1118            MspResponse::MspRawImu(_) => MspCommandCode::MSP_RAW_IMU,
1119            MspResponse::MspDataFlashSummaryReply(_) => MspCommandCode::MSP_DATAFLASH_SUMMARY,
1120            MspResponse::MspDataFlashReply(_) => MspCommandCode::MSP_DATAFLASH_READ,
1121            MspResponse::MspDataFlashRead(_) => MspCommandCode::MSP_DATAFLASH_READ,
1122            MspResponse::MspAccTrim(_) => MspCommandCode::MSP_ACC_TRIM,
1123            MspResponse::MspIdent(_) => MspCommandCode::MSP_IDENT,
1124            MspResponse::MspMisc(_) => MspCommandCode::MSP_MISC,
1125            MspResponse::MspAttitude(_) => MspCommandCode::MSP_ATTITUDE,
1126            MspResponse::MspAltitude(_) => MspCommandCode::MSP_ALTITUDE,
1127            MspResponse::MspBatteryConfig(_) => MspCommandCode::MSP_BATTERY_CONFIG,
1128            MspResponse::MspAnalog(_) => MspCommandCode::MSP_ANALOG,
1129            MspResponse::MspRssiConfig(_) => MspCommandCode::MSP_RSSI_CONFIG,
1130            MspResponse::MspVoltageMeter(_) => MspCommandCode::MSP_VOLTAGE_METERS,
1131            MspResponse::MspCurrentMeter(_) => MspCommandCode::MSP_AMPERAGE_METER_CONFIG,
1132            MspResponse::MspBatteryState(_) => MspCommandCode::MSP_BATTERY_STATE,
1133            MspResponse::MspRcTuning(_) => MspCommandCode::MSP_RC_TUNING,
1134            MspResponse::MspRxConfig(_) => MspCommandCode::MSP_RX_CONFIG,
1135            MspResponse::MspRcChannelValue(_) => MspCommandCode::MSP_RX_MAP,
1136            MspResponse::MspRcMappedChannel(_) => MspCommandCode::MSP_SET_RX_MAP,
1137            MspResponse::MspFeatures(_) => MspCommandCode::MSP_FEATURE,
1138            MspResponse::MspMotor(_) => MspCommandCode::MSP_MOTOR,
1139            MspResponse::MspMotor3DConfig(_) => MspCommandCode::MSP_MOTOR_3D_CONFIG,
1140            MspResponse::MspMotorConfig(_) => MspCommandCode::MSP_MOTOR_CONFIG,
1141            MspResponse::MspRcDeadband(_) => MspCommandCode::MSP_RC_DEADBAND,
1142            MspResponse::MspSensorAlignment(_) => MspCommandCode::MSP_BOARD_ALIGNMENT,
1143            MspResponse::MspAdvancedConfig(_) => MspCommandCode::MSP_ADVANCED_CONFIG,
1144            MspResponse::MspFilterConfig(_) => MspCommandCode::MSP_FILTER_CONFIG,
1145            MspResponse::MspPidAdvanced(_) => MspCommandCode::MSP_PID_ADVANCED,
1146            MspResponse::MspSensorConfig(_) => MspCommandCode::MSP_SENSOR_CONFIG,
1147            MspResponse::MspServos(_) => MspCommandCode::MSP_SERVO,
1148            MspResponse::MspMixerConfig(_) => MspCommandCode::MSP_MIXER,
1149            MspResponse::MspModeRange(_) => MspCommandCode::MSP_MODE_RANGES,
1150            MspResponse::MspSetModeRange(_) => MspCommandCode::MSP_SET_MODE_RANGE,
1151            MspResponse::MspOsdConfig(_) => MspCommandCode::MSP_OSD_CONFIG,
1152            MspResponse::MspSetGetOsdConfig(_) => MspCommandCode::MSP_OSD_CONFIG,
1153            MspResponse::MspSetOsdLayout(_) => MspCommandCode::MSP_OSD_LAYOUT_CONFIG,
1154            MspResponse::MspSetOsdLayoutItem(_) => MspCommandCode::MSP2_INAV_OSD_SET_LAYOUT_ITEM,
1155            MspResponse::MspOsdLayouts(_) => MspCommandCode::MSP2_INAV_OSD_LAYOUTS,
1156            MspResponse::MspSerialSetting(_) => MspCommandCode::MSP2_SET_SERIAL_CONFIG,
1157            MspResponse::MspSettingInfoRequest(_) => MspCommandCode::MSP2_COMMON_SETTING,
1158            MspResponse::MspSettingInfo(_) => MspCommandCode::MSP2_COMMON_SETTING_INFO,
1159            MspResponse::MspRc(_) => MspCommandCode::MSP_RC,
1160            MspResponse::Unknown => MspCommandCode::MSP_API_VERSION,
1161        }
1162    }
1163
1164    pub fn to_bytes(&self) -> Result<MspPacketData, PackingError> {
1165        fn pack_into_packet_data<T: PackedStruct>(
1166            value: &T,
1167        ) -> Result<MspPacketData, PackingError> {
1168            let packed = value.pack()?;
1169            Ok(MspPacketData(SmallVec::from_slice(packed.as_bytes_slice())))
1170        }
1171
1172        match self {
1173            MspResponse::MspApiVersion(data) => pack_into_packet_data(data),
1174            MspResponse::MspFlightControllerVariant(data) => pack_into_packet_data(data),
1175            MspResponse::MspStatus(data) => pack_into_packet_data(data),
1176            MspResponse::MspStatusEx(data) => pack_into_packet_data(data),
1177            MspResponse::MspBfConfig(data) => pack_into_packet_data(data),
1178            MspResponse::MspRawImu(data) => pack_into_packet_data(data),
1179            MspResponse::MspDataFlashSummaryReply(data) => pack_into_packet_data(data),
1180            MspResponse::MspDataFlashReply(data) => pack_into_packet_data(data),
1181            MspResponse::MspDataFlashRead(data) => pack_into_packet_data(data),
1182            MspResponse::MspAccTrim(data) => pack_into_packet_data(data),
1183            MspResponse::MspIdent(data) => pack_into_packet_data(data),
1184            MspResponse::MspMisc(data) => pack_into_packet_data(data),
1185            MspResponse::MspAttitude(data) => pack_into_packet_data(data),
1186            MspResponse::MspAltitude(data) => pack_into_packet_data(data),
1187            MspResponse::MspBatteryConfig(data) => pack_into_packet_data(data),
1188            MspResponse::MspAnalog(data) => pack_into_packet_data(data),
1189            MspResponse::MspRssiConfig(data) => pack_into_packet_data(data),
1190            MspResponse::MspVoltageMeter(data) => pack_into_packet_data(data),
1191            MspResponse::MspCurrentMeter(data) => pack_into_packet_data(data),
1192            MspResponse::MspBatteryState(data) => pack_into_packet_data(data),
1193            MspResponse::MspRcTuning(data) => pack_into_packet_data(data),
1194            MspResponse::MspRxConfig(data) => pack_into_packet_data(data),
1195            MspResponse::MspRcChannelValue(data) => pack_into_packet_data(data),
1196            MspResponse::MspRcMappedChannel(data) => pack_into_packet_data(data),
1197            MspResponse::MspFeatures(data) => pack_into_packet_data(data),
1198            MspResponse::MspMotor(data) => pack_into_packet_data(data),
1199            MspResponse::MspMotor3DConfig(data) => pack_into_packet_data(data),
1200            MspResponse::MspMotorConfig(data) => pack_into_packet_data(data),
1201            MspResponse::MspRcDeadband(data) => pack_into_packet_data(data),
1202            MspResponse::MspSensorAlignment(data) => pack_into_packet_data(data),
1203            MspResponse::MspAdvancedConfig(data) => pack_into_packet_data(data),
1204            MspResponse::MspFilterConfig(data) => pack_into_packet_data(data),
1205            MspResponse::MspPidAdvanced(data) => pack_into_packet_data(data),
1206            MspResponse::MspSensorConfig(data) => pack_into_packet_data(data),
1207            MspResponse::MspServos(data) => pack_into_packet_data(data),
1208            MspResponse::MspMixerConfig(data) => pack_into_packet_data(data),
1209            MspResponse::MspModeRange(data) => pack_into_packet_data(data),
1210            MspResponse::MspSetModeRange(data) => pack_into_packet_data(data),
1211            MspResponse::MspOsdConfig(data) => pack_into_packet_data(data),
1212            MspResponse::MspSetGetOsdConfig(data) => pack_into_packet_data(data),
1213            MspResponse::MspSetOsdLayout(data) => pack_into_packet_data(data),
1214            MspResponse::MspSetOsdLayoutItem(data) => pack_into_packet_data(data),
1215            MspResponse::MspOsdLayouts(data) => pack_into_packet_data(data),
1216            MspResponse::MspSerialSetting(data) => pack_into_packet_data(data),
1217            MspResponse::MspSettingInfoRequest(data) => pack_into_packet_data(data),
1218            MspResponse::MspSettingInfo(data) => pack_into_packet_data(data),
1219            MspResponse::MspRc(data) => pack_into_packet_data(data),
1220            MspResponse::Unknown => Err(PackingError::InvalidValue),
1221        }
1222    }
1223}
1224
1225impl From<MspResponse> for MspPacket {
1226    fn from(command: MspResponse) -> Self {
1227        MspPacket {
1228            cmd: command.command_code().to_primitive(),
1229            direction: FromFlightController,
1230            data: command.to_bytes().unwrap(), // should always be able to serialize a constructed MSPCommand
1231        }
1232    }
1233}
1234impl From<MspPacket> for MspResponse {
1235    fn from(packet: MspPacket) -> Self {
1236        match packet.cmd.into() {
1237            MspCommandCode::MSP_API_VERSION => {
1238                MspResponse::MspApiVersion(packet.decode_as::<MspApiVersion>().unwrap())
1239            }
1240            MspCommandCode::MSP_FC_VARIANT => MspResponse::MspFlightControllerVariant(
1241                packet.decode_as::<MspFlightControllerVariant>().unwrap(),
1242            ),
1243            MspCommandCode::MSP_STATUS => {
1244                MspResponse::MspStatus(packet.decode_as::<MspStatus>().unwrap())
1245            }
1246            MspCommandCode::MSP_STATUS_EX => {
1247                MspResponse::MspStatusEx(packet.decode_as::<MspStatusEx>().unwrap())
1248            }
1249            MspCommandCode::MSP_BF_CONFIG => {
1250                MspResponse::MspBfConfig(packet.decode_as::<MspBfConfig>().unwrap())
1251            }
1252            MspCommandCode::MSP_RAW_IMU => {
1253                MspResponse::MspRawImu(packet.decode_as::<MspRawImu>().unwrap())
1254            }
1255            MspCommandCode::MSP_DATAFLASH_SUMMARY => MspResponse::MspDataFlashSummaryReply(
1256                packet.decode_as::<MspDataFlashSummaryReply>().unwrap(),
1257            ),
1258            MspCommandCode::MSP_DATAFLASH_READ => {
1259                MspResponse::MspDataFlashReply(packet.decode_as::<MspDataFlashReply>().unwrap())
1260            }
1261            MspCommandCode::MSP_ACC_TRIM => {
1262                MspResponse::MspAccTrim(packet.decode_as::<MspAccTrim>().unwrap())
1263            }
1264            MspCommandCode::MSP_IDENT => {
1265                MspResponse::MspIdent(packet.decode_as::<MspIdent>().unwrap())
1266            }
1267            MspCommandCode::MSP_MISC => {
1268                MspResponse::MspMisc(packet.decode_as::<MspMisc>().unwrap())
1269            }
1270            MspCommandCode::MSP_ATTITUDE => {
1271                MspResponse::MspAttitude(packet.decode_as::<MspAttitude>().unwrap())
1272            }
1273            MspCommandCode::MSP_ALTITUDE => {
1274                MspResponse::MspAltitude(packet.decode_as::<MspAltitude>().unwrap())
1275            }
1276            MspCommandCode::MSP_BATTERY_CONFIG => {
1277                MspResponse::MspBatteryConfig(packet.decode_as::<MspBatteryConfig>().unwrap())
1278            }
1279            MspCommandCode::MSP_ANALOG => {
1280                MspResponse::MspAnalog(packet.decode_as::<MspAnalog>().unwrap())
1281            }
1282            MspCommandCode::MSP_RSSI_CONFIG => {
1283                MspResponse::MspRssiConfig(packet.decode_as::<MspRssiConfig>().unwrap())
1284            }
1285            MspCommandCode::MSP_VOLTAGE_METERS => {
1286                MspResponse::MspVoltageMeter(packet.decode_as::<MspVoltageMeter>().unwrap())
1287            }
1288            MspCommandCode::MSP_AMPERAGE_METER_CONFIG => {
1289                MspResponse::MspCurrentMeter(packet.decode_as::<MspCurrentMeter>().unwrap())
1290            }
1291            MspCommandCode::MSP_BATTERY_STATE => {
1292                MspResponse::MspBatteryState(packet.decode_as::<MspBatteryState>().unwrap())
1293            }
1294            MspCommandCode::MSP_RC_TUNING => {
1295                MspResponse::MspRcTuning(packet.decode_as::<MspRcTuning>().unwrap())
1296            }
1297            MspCommandCode::MSP_RX_CONFIG => {
1298                MspResponse::MspRxConfig(packet.decode_as::<MspRxConfig>().unwrap())
1299            }
1300            MspCommandCode::MSP_RX_MAP => {
1301                MspResponse::MspRcChannelValue(packet.decode_as::<MspRcChannelValue>().unwrap())
1302            }
1303            MspCommandCode::MSP_SET_RX_MAP => {
1304                MspResponse::MspRcMappedChannel(packet.decode_as::<MspRcMappedChannel>().unwrap())
1305            }
1306            MspCommandCode::MSP_FEATURE => {
1307                MspResponse::MspFeatures(packet.decode_as::<MspFeatures>().unwrap())
1308            }
1309            MspCommandCode::MSP_MOTOR => {
1310                MspResponse::MspMotor(packet.decode_as::<MspMotor>().unwrap())
1311            }
1312            MspCommandCode::MSP_MOTOR_3D_CONFIG => {
1313                MspResponse::MspMotor3DConfig(packet.decode_as::<MspMotor3DConfig>().unwrap())
1314            }
1315            MspCommandCode::MSP_MOTOR_CONFIG => {
1316                MspResponse::MspMotorConfig(packet.decode_as::<MspMotorConfig>().unwrap())
1317            }
1318            MspCommandCode::MSP_RC_DEADBAND => {
1319                MspResponse::MspRcDeadband(packet.decode_as::<MspRcDeadband>().unwrap())
1320            }
1321            MspCommandCode::MSP_BOARD_ALIGNMENT => {
1322                MspResponse::MspSensorAlignment(packet.decode_as::<MspSensorAlignment>().unwrap())
1323            }
1324            MspCommandCode::MSP_ADVANCED_CONFIG => {
1325                MspResponse::MspAdvancedConfig(packet.decode_as::<MspAdvancedConfig>().unwrap())
1326            }
1327            MspCommandCode::MSP_FILTER_CONFIG => {
1328                MspResponse::MspFilterConfig(packet.decode_as::<MspFilterConfig>().unwrap())
1329            }
1330            MspCommandCode::MSP_PID_ADVANCED => {
1331                MspResponse::MspPidAdvanced(packet.decode_as::<MspPidAdvanced>().unwrap())
1332            }
1333            MspCommandCode::MSP_SENSOR_CONFIG => {
1334                MspResponse::MspSensorConfig(packet.decode_as::<MspSensorConfig>().unwrap())
1335            }
1336            MspCommandCode::MSP_SERVO => {
1337                MspResponse::MspServos(packet.decode_as::<MspServos>().unwrap())
1338            }
1339            MspCommandCode::MSP_MIXER => {
1340                MspResponse::MspMixerConfig(packet.decode_as::<MspMixerConfig>().unwrap())
1341            }
1342            MspCommandCode::MSP_MODE_RANGES => {
1343                MspResponse::MspModeRange(packet.decode_as::<MspModeRange>().unwrap())
1344            }
1345            MspCommandCode::MSP_SET_MODE_RANGE => {
1346                MspResponse::MspSetModeRange(packet.decode_as::<MspSetModeRange>().unwrap())
1347            }
1348            MspCommandCode::MSP_OSD_CONFIG => {
1349                MspResponse::MspOsdConfig(packet.decode_as::<MspOsdConfig>().unwrap())
1350            }
1351            MspCommandCode::MSP_OSD_LAYOUT_CONFIG => {
1352                MspResponse::MspSetOsdLayout(packet.decode_as::<MspSetOsdLayout>().unwrap())
1353            }
1354            MspCommandCode::MSP2_INAV_OSD_SET_LAYOUT_ITEM => {
1355                MspResponse::MspSetOsdLayoutItem(packet.decode_as::<MspSetOsdLayoutItem>().unwrap())
1356            }
1357            MspCommandCode::MSP2_INAV_OSD_LAYOUTS => {
1358                MspResponse::MspOsdLayouts(packet.decode_as::<MspOsdLayouts>().unwrap())
1359            }
1360            MspCommandCode::MSP2_SET_SERIAL_CONFIG => {
1361                MspResponse::MspSerialSetting(packet.decode_as::<MspSerialSetting>().unwrap())
1362            }
1363            MspCommandCode::MSP2_COMMON_SETTING => MspResponse::MspSettingInfoRequest(
1364                packet.decode_as::<MspSettingInfoRequest>().unwrap(),
1365            ),
1366            MspCommandCode::MSP2_COMMON_SETTING_INFO => {
1367                MspResponse::MspSettingInfo(packet.decode_as::<MspSettingInfo>().unwrap())
1368            }
1369            MspCommandCode::MSP_RC => MspResponse::MspRc(packet.decode_as::<MspRc>().unwrap()),
1370            _ => MspResponse::Unknown,
1371        }
1372    }
1373}
1374
1375#[cfg(test)]
1376mod tests {
1377    use super::*;
1378    #[test]
1379    fn test_mixer() {
1380        use packed_struct::prelude::*;
1381
1382        let m = MspMixerConfig {
1383            mixer_mode: MixerMode::QuadX,
1384        };
1385        assert_eq!(3, m.mixer_mode.to_primitive());
1386        let r = m.pack().unwrap();
1387        assert_eq!(3, r.as_slice()[0]);
1388    }
1389
1390    #[test]
1391    #[cfg(feature = "bincode")]
1392    fn test_command_enum_with_bincode() {
1393        let command = MspResponse::MspApiVersion(MspApiVersion {
1394            protocol_version: 1,
1395            api_version_major: 2,
1396            api_version_minor: 3,
1397        });
1398
1399        let encoded = bincode::encode_to_vec(&command, bincode::config::standard()).unwrap();
1400        let decoded: MspResponse =
1401            bincode::decode_from_slice(&encoded, bincode::config::standard())
1402                .unwrap()
1403                .0;
1404
1405        match (command, decoded) {
1406            (MspResponse::MspApiVersion(c1), MspResponse::MspApiVersion(c2)) => {
1407                assert_eq!(c1.protocol_version, c2.protocol_version);
1408                assert_eq!(c1.api_version_major, c2.api_version_major);
1409                assert_eq!(c1.api_version_minor, c2.api_version_minor);
1410            }
1411            _ => panic!("Decoded command does not match the original command"),
1412        }
1413    }
1414}