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