diff --git a/.config/_typos.toml b/.config/_typos.toml index 50611f212..81c16d97f 100644 --- a/.config/_typos.toml +++ b/.config/_typos.toml @@ -1,3 +1,4 @@ [default.extend-words] mis = "mis" ratatui = "ratatui" +thr = "thr" diff --git a/Cargo.toml b/Cargo.toml index 9029570bf..91b8ae712 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -14,6 +14,7 @@ members = [ "core/cu29_soa_derive", "core/cu29_traits", "core/cu29_unifiedlog", + "components/common/cu_msplib", "components/monitors/cu_consolemon", "components/payloads/cu_sensor_payloads", "components/payloads/cu_spatial_payloads", diff --git a/components/common/cu_msplib/Cargo.toml b/components/common/cu_msplib/Cargo.toml new file mode 100644 index 000000000..aa7edfaee --- /dev/null +++ b/components/common/cu_msplib/Cargo.toml @@ -0,0 +1,18 @@ +[package] +name = "cu_msplib" +version.workspace = true +authors.workspace = true +edition.workspace = true +license.workspace = true +keywords.workspace = true +categories.workspace = true +homepage.workspace = true +repository.workspace = true + +[dependencies] +anyhow = "1.0.96" +serialport = "4.7.0" +crc-any = "2.5.0" +smallvec = "1.14.0" +packed_struct = "0.10.1" +serde = { version = "1.0.218", features = ["derive"] } \ No newline at end of file diff --git a/components/common/cu_msplib/README.md b/components/common/cu_msplib/README.md new file mode 100644 index 000000000..6d71c8d2d --- /dev/null +++ b/components/common/cu_msplib/README.md @@ -0,0 +1,5 @@ +## Multiwii Serial Protocol + +This is a spin on: https://docs.rs/multiwii_serial_protocol_v2/latest/multiwii_serial_protocol_v2/ + +The main difference are optimizations and cleanups. \ No newline at end of file diff --git a/components/common/cu_msplib/src/commands.rs b/components/common/cu_msplib/src/commands.rs new file mode 100644 index 000000000..358f4683b --- /dev/null +++ b/components/common/cu_msplib/src/commands.rs @@ -0,0 +1,195 @@ +use packed_struct::derive::PrimitiveEnum; +use packed_struct::PrimitiveEnum; + +#[derive(PrimitiveEnum, Debug, Copy, Clone, PartialEq)] +#[allow(non_camel_case_types)] +/// MSP command values, used for command encapsulation +pub enum MspCommandCode { + MSP_API_VERSION = 1, + MSP_FC_VARIANT = 2, + MSP_FC_VERSION = 3, + MSP_BOARD_INFO = 4, + MSP_BUILD_INFO = 5, + + // MSP commands for Cleanflight original features + MSP_BATTERY_CONFIG = 32, + MSP_SET_BATTERY_CONFIG = 33, + MSP_MODE_RANGES = 34, + MSP_SET_MODE_RANGE = 35, + MSP_FEATURE = 36, + MSP_SET_FEATURE = 37, + MSP_BOARD_ALIGNMENT = 38, + MSP_SET_BOARD_ALIGNMENT = 39, + MSP_AMPERAGE_METER_CONFIG = 40, + MSP_SET_AMPERAGE_METER_CONFIG = 41, + MSP_MIXER = 42, + MSP_SET_MIXER = 43, + MSP_RX_CONFIG = 44, + MSP_SET_RX_CONFIG = 45, + MSP_LED_COLORS = 46, + MSP_SET_LED_COLORS = 47, + MSP_LED_STRIP_CONFIG = 48, + MSP_SET_LED_STRIP_CONFIG = 49, + MSP_RSSI_CONFIG = 50, + MSP_SET_RSSI_CONFIG = 51, + MSP_ADJUSTMENT_RANGES = 52, + MSP_SET_ADJUSTMENT_RANGE = 53, + MSP_CF_SERIAL_CONFIG = 54, + MSP_SET_CF_SERIAL_CONFIG = 55, + MSP_VOLTAGE_METER_CONFIG = 56, + MSP_SET_VOLTAGE_METER_CONFIG = 57, + MSP_SONAR = 58, + MSP_PID_CONTROLLER = 59, + MSP_SET_PID_CONTROLLER = 60, + MSP_ARMING_CONFIG = 61, + MSP_SET_ARMING_CONFIG = 62, + MSP_DATAFLASH_SUMMARY = 70, + MSP_DATAFLASH_READ = 71, + MSP_DATAFLASH_ERASE = 72, + MSP_LOOP_TIME = 73, + MSP_SET_LOOP_TIME = 74, + MSP_FAILSAFE_CONFIG = 75, + MSP_SET_FAILSAFE_CONFIG = 76, + MSP_RXFAIL_CONFIG = 77, + MSP_SET_RXFAIL_CONFIG = 78, + MSP_SDCARD_SUMMARY = 79, + MSP_BLACKBOX_CONFIG = 80, + MSP_SET_BLACKBOX_CONFIG = 81, + MSP_TRANSPONDER_CONFIG = 82, + MSP_SET_TRANSPONDER_CONFIG = 83, + + MSP_OSD_CONFIG = 84, //out message Get osd settings - baseflight + MSP_SET_OSD_CONFIG = 85, //in message Set osd settings - baseflight + + MSP_OSD_CHAR_READ = 86, //out message Get osd settings - betaflight + MSP_OSD_CHAR_WRITE = 87, //in message Set osd settings - betaflight + + MSP_LED_STRIP_MODECOLOR = 127, + MSP_SET_LED_STRIP_MODECOLOR = 221, + + MSP_VOLTAGE_METERS = 128, + MSP_AMPERAGE_METERS = 129, + MSP_BATTERY_STATE = 130, + + MSP_MOTOR_CONFIG = 131, + + // OSD commands + MSP_OSD_VIDEO_CONFIG = 180, + MSP_SET_OSD_VIDEO_CONFIG = 181, + MSP_OSD_VIDEO_STATUS = 182, + MSP_OSD_ELEMENT_SUMMARY = 183, + MSP_OSD_LAYOUT_CONFIG = 184, + MSP_SET_OSD_LAYOUT_CONFIG = 185, + + // Multiwii MSP commands + MSP_IDENT = 100, + MSP_STATUS = 101, + MSP_RAW_IMU = 102, + MSP_SERVO = 103, + MSP_MOTOR = 104, + MSP_RC = 105, + MSP_RAW_GPS = 106, + MSP_COMP_GPS = 107, + MSP_ATTITUDE = 108, + MSP_ALTITUDE = 109, + MSP_ANALOG = 110, + MSP_RC_TUNING = 111, + MSP_PID = 112, + MSP_BOX = 113, + MSP_MISC = 114, + MSP_MOTOR_PINS = 115, + MSP_BOXNAMES = 116, + MSP_PIDNAMES = 117, + MSP_WP = 118, + MSP_BOXIDS = 119, + MSP_SERVO_CONFIGURATIONS = 120, + MSP_MOTOR_3D_CONFIG = 124, + MSP_RC_DEADBAND = 125, + MSP_SENSOR_ALIGNMENT = 126, + + MSP_SET_RAW_RC = 200, + MSP_SET_RAW_GPS = 201, + MSP_SET_PID = 202, + MSP_SET_BOX = 203, + MSP_SET_RC_TUNING = 204, + MSP_ACC_CALIBRATION = 205, + MSP_MAG_CALIBRATION = 206, + MSP_SET_MISC = 207, + MSP_RESET_CONF = 208, + MSP_SET_WP = 209, + MSP_SELECT_SETTING = 210, + MSP_SET_HEAD = 211, + MSP_SET_SERVO_CONFIGURATION = 212, + MSP_SET_MOTOR = 214, + MSP_SET_3D = 217, + MSP_SET_RC_DEADBAND = 218, + MSP_SET_RESET_CURR_PID = 219, + MSP_SET_SENSOR_ALIGNMENT = 220, + + // MSP_BIND = 240, + MSP_SERVO_MIX_RULES = 241, + MSP_SET_SERVO_MIX_RULE = 242, + + MSP_EEPROM_WRITE = 250, + + MSP_DEBUGMSG = 253, + MSP_DEBUG = 254, + + MSP_BF_CONFIG = 66, + + // Additional baseflight commands that are not compatible with MultiWii + MSP_UID = 160, // Unique device ID + MSP_STATUS_EX = 150, // cycletime, errors_count, CPU load, sensor present etc + MSP_ACC_TRIM = 240, // get acc angle trim values + MSP_SET_ACC_TRIM = 239, // set acc angle trim values + MSP_GPS_SV_INFO = 164, // get Signal Strength + + // Additional private MSP for baseflight configurator + MSP_RX_MAP = 64, // get channel map (also returns number of channels total) + MSP_SET_RX_MAP = 65, // set rc map, numchannels to set comes from MSP_RX_MAP + + MSP_SET_REBOOT = 68, // reboot settings + MSP_BF_BUILD_INFO = 69, // build date as well as some space for future expansion, + + // Betaflight + MSP_ADVANCED_CONFIG = 90, + MSP_SET_ADVANCED_CONFIG = 91, + + MSP_FILTER_CONFIG = 92, + MSP_SET_FILTER_CONFIG = 93, + + MSP_PID_ADVANCED = 94, + MSP_SET_PID_ADVANCED = 95, + + MSP_SENSOR_CONFIG = 96, + MSP_SET_SENSOR_CONFIG = 97, + + // Inav + MSP2_COMMON_SETTING = 0x1003, //in/out message Returns the value for a setting + MSP2_COMMON_SET_SETTING = 0x1004, //in message Sets the value for a setting + + MSP2_MOTOR_MIXER = 0x1005, + MSP2_SET_MOTOR_MIXER = 0x1006, + + MSP2_COMMON_SETTING_INFO = 0x1007, + MSP2_COMMON_PG_LIST = 0x1008, + + MSP2_SERIAL_CONFIG = 0x1009, + MSP2_SET_SERIAL_CONFIG = 0x100A, + + MSP2_INAV_OSD_LAYOUTS = 0x2012, + MSP2_INAV_OSD_SET_LAYOUT_ITEM = 0x2013, + MSP2_INAV_OSD_ALARMS = 0x2014, + MSP2_INAV_OSD_SET_ALARMS = 0x2015, + MSP2_INAV_OSD_PREFERENCES = 0x2016, + MSP2_INAV_OSD_SET_PREFERENCES = 0x2017, + + MSP2_INAV_SERVO_MIXER = 0x2020, + MSP2_INAV_SET_SERVO_MIXER = 0x2021, +} + +impl From for MspCommandCode { + fn from(value: u16) -> Self { + Self::from_primitive(value).unwrap_or_else(|| panic!("Invalid MSP command code: {}", value)) + } +} diff --git a/components/common/cu_msplib/src/lib.rs b/components/common/cu_msplib/src/lib.rs new file mode 100644 index 000000000..20e70f24d --- /dev/null +++ b/components/common/cu_msplib/src/lib.rs @@ -0,0 +1,485 @@ +pub mod commands; +pub mod structs; + +use crc_any::CRCu8; +use packed_struct::PackedStruct; +use smallvec::SmallVec; +use std::fmt::{Debug, Formatter}; +use std::{fmt, mem}; + +#[derive(Clone, PartialEq)] +pub struct MspPacketData(pub(crate) SmallVec<[u8; 256]>); + +impl MspPacketData { + pub(crate) fn new() -> MspPacketData { + MspPacketData(SmallVec::new()) + } + + pub fn as_mut_slice(&mut self) -> &mut [u8] { + let MspPacketData(data) = self; + data.as_mut_slice() + } +} +// By definition an MSP packet cannot be larger than 255 bytes + +impl Debug for MspPacketData { + fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result { + let MspPacketData(data) = self; + if data.is_empty() { + write!(f, "empty")?; + return Ok(()); + } + write!(f, "0x")?; + for byte in data { + write!(f, "{:02X}", byte)?; + } + Ok(()) + } +} + +impl From<&[u8]> for MspPacketData { + fn from(data: &[u8]) -> Self { + MspPacketData(SmallVec::from_slice(data)) + } +} + +impl MspPacketData { + pub fn as_slice(&self) -> &[u8] { + let Self(data) = self; + data + } +} + +/// Packet parsing error +#[derive(Copy, Clone, Debug, PartialEq)] +pub enum MspPacketParseError { + OutputBufferSizeMismatch, + CrcMismatch { expected: u8, calculated: u8 }, + InvalidData, + InvalidHeader1, + InvalidHeader2, + InvalidDirection, + InvalidDataLength, +} + +/// Packet's desired destination +#[derive(Copy, Clone, Debug, PartialEq)] +pub enum MspPacketDirection { + /// Network byte '<' + ToFlightController, + /// Network byte '>' + FromFlightController, + /// Network byte '!' + Unsupported, +} + +impl MspPacketDirection { + /// To network byte + pub fn to_byte(&self) -> u8 { + let b = match *self { + MspPacketDirection::ToFlightController => '<', + MspPacketDirection::FromFlightController => '>', + MspPacketDirection::Unsupported => '!', + }; + b as u8 + } +} + +#[derive(Debug, Clone, PartialEq)] +/// A decoded MSP packet, with a command code, direction and payload +pub struct MspPacket { + pub cmd: u16, + pub direction: MspPacketDirection, + pub data: MspPacketData, +} + +#[derive(Copy, Clone, PartialEq, Debug)] +enum MspParserState { + Header1, + Header2, + Direction, + FlagV2, + DataLength, + DataLengthV2, + Command, + CommandV2, + Data, + DataV2, + Crc, +} + +#[derive(Copy, Clone, PartialEq, Debug)] +enum MspVersion { + V1, + V2, +} + +#[derive(Debug)] +/// Parser that can find packets from a raw byte stream +pub struct MspParser { + state: MspParserState, + packet_version: MspVersion, + packet_direction: MspPacketDirection, + packet_cmd: u16, + packet_data_length_remaining: usize, + packet_data: MspPacketData, + packet_crc: u8, + packet_crc_v2: CRCu8, +} + +impl MspParser { + /// Create a new parser + pub fn new() -> MspParser { + Self { + state: MspParserState::Header1, + packet_version: MspVersion::V1, + packet_direction: MspPacketDirection::ToFlightController, + packet_data_length_remaining: 0, + packet_cmd: 0, + packet_data: MspPacketData::new(), + packet_crc: 0, + packet_crc_v2: CRCu8::crc8dvb_s2(), + } + } + + /// Are we waiting for the header of a brand new packet? + pub fn state_is_between_packets(&self) -> bool { + self.state == MspParserState::Header1 + } + + /// Parse the next input byte. Returns a valid packet whenever a full packet is received, otherwise + /// restarts the state of the parser. + pub fn parse(&mut self, input: u8) -> Result, MspPacketParseError> { + match self.state { + MspParserState::Header1 => { + if input == b'$' { + self.state = MspParserState::Header2; + } else { + self.reset(); + } + } + + MspParserState::Header2 => { + self.packet_version = match input as char { + 'M' => MspVersion::V1, + 'X' => MspVersion::V2, + _ => { + self.reset(); + return Err(MspPacketParseError::InvalidHeader2); + } + }; + + self.state = MspParserState::Direction; + } + + MspParserState::Direction => { + match input { + 60 => self.packet_direction = MspPacketDirection::ToFlightController, // '>' + 62 => self.packet_direction = MspPacketDirection::FromFlightController, // '<' + 33 => self.packet_direction = MspPacketDirection::Unsupported, // '!' error + _ => { + self.reset(); + return Err(MspPacketParseError::InvalidDirection); + } + } + + self.state = match self.packet_version { + MspVersion::V1 => MspParserState::DataLength, + MspVersion::V2 => MspParserState::FlagV2, + }; + } + + MspParserState::FlagV2 => { + // uint8, flag, usage to be defined (set to zero) + self.state = MspParserState::CommandV2; + self.packet_data = MspPacketData::new(); + self.packet_crc_v2.digest(&[input]); + } + + MspParserState::CommandV2 => { + let MspPacketData(data) = &mut self.packet_data; + data.push(input); + + if data.len() == 2 { + let mut s = [0u8; size_of::()]; + s.copy_from_slice(data); + self.packet_cmd = u16::from_le_bytes(s); + + self.packet_crc_v2.digest(&data); + data.clear(); + self.state = MspParserState::DataLengthV2; + } + } + + MspParserState::DataLengthV2 => { + let MspPacketData(data) = &mut self.packet_data; + data.push(input); + + if data.len() == 2 { + let mut s = [0u8; size_of::()]; + s.copy_from_slice(data); + self.packet_data_length_remaining = u16::from_le_bytes(s).into(); + self.packet_crc_v2.digest(data); + data.clear(); + if self.packet_data_length_remaining == 0 { + self.state = MspParserState::Crc; + } else { + self.state = MspParserState::DataV2; + } + } + } + + MspParserState::DataV2 => { + let MspPacketData(data) = &mut self.packet_data; + data.push(input); + self.packet_data_length_remaining -= 1; + + if self.packet_data_length_remaining == 0 { + self.state = MspParserState::Crc; + } + } + + MspParserState::DataLength => { + let MspPacketData(data) = &mut self.packet_data; + self.packet_data_length_remaining = input as usize; + self.state = MspParserState::Command; + self.packet_crc ^= input; + data.clear(); + } + + MspParserState::Command => { + self.packet_cmd = input as u16; + + if self.packet_data_length_remaining == 0 { + self.state = MspParserState::Crc; + } else { + self.state = MspParserState::Data; + } + + self.packet_crc ^= input; + } + + MspParserState::Data => { + let MspPacketData(data) = &mut self.packet_data; + data.push(input); + self.packet_data_length_remaining -= 1; + + self.packet_crc ^= input; + + if self.packet_data_length_remaining == 0 { + self.state = MspParserState::Crc; + } + } + + MspParserState::Crc => { + let MspPacketData(data) = &mut self.packet_data; + if self.packet_version == MspVersion::V2 { + self.packet_crc_v2.digest(data); + self.packet_crc = self.packet_crc_v2.get_crc(); + } + + let packet_crc = self.packet_crc; + if input != packet_crc { + self.reset(); + return Err(MspPacketParseError::CrcMismatch { + expected: input, + calculated: packet_crc, + }); + } + + let mut n = MspPacketData::new(); + mem::swap(&mut self.packet_data, &mut n); + + let packet = MspPacket { + cmd: self.packet_cmd, + direction: self.packet_direction, + data: n, + }; + + self.reset(); + + return Ok(Some(packet)); + } + } + + Ok(None) + } + + pub fn reset(&mut self) { + let MspPacketData(data) = &mut self.packet_data; + self.state = MspParserState::Header1; + self.packet_direction = MspPacketDirection::ToFlightController; + self.packet_data_length_remaining = 0; + self.packet_cmd = 0; + data.clear(); + self.packet_crc = 0; + self.packet_crc_v2.reset(); + } +} + +impl Default for MspParser { + fn default() -> Self { + Self::new() + } +} + +impl MspPacket { + /// Number of bytes that this packet requires to be packed + pub fn packet_size_bytes(&self) -> usize { + let MspPacketData(data) = &self.data; + 6 + data.len() + } + + /// Number of bytes that this packet requires to be packed + pub fn packet_size_bytes_v2(&self) -> usize { + let MspPacketData(data) = &self.data; + 9 + data.len() + } + + /// Serialize to network bytes + pub fn serialize(&self, output: &mut [u8]) -> Result<(), MspPacketParseError> { + let MspPacketData(data) = &self.data; + let l = output.len(); + + if l != self.packet_size_bytes() { + return Err(MspPacketParseError::OutputBufferSizeMismatch); + } + + output[0] = b'$'; + output[1] = b'M'; + output[2] = self.direction.to_byte(); + output[3] = data.len() as u8; + output[4] = self.cmd as u8; + + output[5..l - 1].copy_from_slice(data); + + let mut crc = output[3] ^ output[4]; + for b in data { + crc ^= *b; + } + output[l - 1] = crc; + + Ok(()) + } + + /// Serialize to network bytes + pub fn serialize_v2(&self, output: &mut [u8]) -> Result<(), MspPacketParseError> { + let MspPacketData(data) = &self.data; + let l = output.len(); + + if l != self.packet_size_bytes_v2() { + return Err(MspPacketParseError::OutputBufferSizeMismatch); + } + + output[0] = b'$'; + output[1] = b'X'; + output[2] = self.direction.to_byte(); + output[3] = 0; + output[4..6].copy_from_slice(&self.cmd.to_le_bytes()); + output[6..8].copy_from_slice(&(data.len() as u16).to_le_bytes()); + + output[8..l - 1].copy_from_slice(data); + + let mut crc = CRCu8::crc8dvb_s2(); + crc.digest(&output[3..l - 1]); + output[l - 1] = crc.get_crc(); + + Ok(()) + } + + pub fn decode_as(&self) -> Result { + let expected_size = size_of::(); + + if self.data.0.len() < expected_size { + return Err(packed_struct::PackingError::BufferSizeMismatch { + expected: expected_size, + actual: self.data.0.len(), + }); + } + + let byte_array: &T::ByteArray = unsafe { &*(self.data.0.as_ptr() as *const T::ByteArray) }; + + T::unpack(byte_array) + } +} + +#[cfg(test)] +mod tests { + use super::*; + use smallvec::smallvec; + #[test] + fn test_serialize() { + let packet = MspPacket { + cmd: 2, + direction: MspPacketDirection::ToFlightController, + data: MspPacketData(smallvec![0xbe, 0xef]), + }; + + let size = packet.packet_size_bytes(); + assert_eq!(8, size); + + let mut output = vec![0; size]; + packet.serialize(&mut output).unwrap(); + let expected = [b'$', b'M', b'<', 2, 2, 0xbe, 0xef, 81]; + assert_eq!(&expected, output.as_slice()); + + let mut packet_parsed = None; + let mut parser = MspParser::new(); + for b in output { + let s = parser.parse(b); + if let Ok(Some(p)) = s { + packet_parsed = Some(p); + break; + } + } + + assert_eq!(packet, packet_parsed.unwrap()); + } + + #[test] + fn test_roundtrip() { + fn roundtrip(packet: &MspPacket) { + let size = packet.packet_size_bytes(); + let mut output = vec![0; size]; + + packet.serialize(&mut output).unwrap(); + let mut parser = MspParser::new(); + let mut packet_parsed = None; + for b in output { + let s = parser.parse(b); + if let Ok(Some(p)) = s { + packet_parsed = Some(p); + break; + } + } + assert_eq!(packet, &packet_parsed.unwrap()); + } + + { + let packet = MspPacket { + cmd: 1, + direction: MspPacketDirection::ToFlightController, + data: MspPacketData(smallvec![0x00, 0x00, 0x00]), + }; + roundtrip(&packet); + } + + { + let packet = MspPacket { + cmd: 200, + direction: MspPacketDirection::FromFlightController, + data: MspPacketData::new(), + }; + roundtrip(&packet); + } + + { + let packet = MspPacket { + cmd: 100, + direction: MspPacketDirection::Unsupported, + data: MspPacketData(smallvec![0x44, 0x20, 0x00, 0x80]), + }; + roundtrip(&packet); + } + } +} diff --git a/components/common/cu_msplib/src/structs.rs b/components/common/cu_msplib/src/structs.rs new file mode 100644 index 000000000..0412019db --- /dev/null +++ b/components/common/cu_msplib/src/structs.rs @@ -0,0 +1,870 @@ +//! MSP structures + +use packed_struct::derive::{PackedStruct, PrimitiveEnum}; +use serde::{Deserialize, Serialize}; + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspApiVersion { + pub protocol_version: u8, + pub api_version_major: u8, + pub api_version_minor: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspFlightControllerVariant { + pub identifier: [u8; 4], +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspFlightControllerVersion { + pub major: u8, + pub minor: u8, + pub patch: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspBoardInfo { + pub board_id: [u8; 4], + pub hardware_revision: u16, + pub fc_type: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspBuildInfo { + pub date_str: [u8; 11], + pub time_str: [u8; 8], + pub git_str: [u8; 7], +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspUniqueId { + pub uid: [u8; 12], +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspAvailableSensors { + #[packed_field(bits = "2")] + pub sonar: bool, + #[packed_field(bits = "4")] + pub gps: bool, + #[packed_field(bits = "5")] + pub mag: bool, + #[packed_field(bits = "6")] + pub baro: bool, + #[packed_field(bits = "7")] + pub acc: bool, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspStatus { + pub cycle_time: u16, + pub i2c_errors: u16, + #[packed_field(size_bits = "8")] + pub sensors: MspAvailableSensors, + pub null1: u8, + pub flight_mode: u32, + pub profile: u8, + pub system_load: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspStatusEx { + pub cycle_time: u16, + pub i2c_errors: u16, + #[packed_field(size_bits = "8")] + pub sensors: MspAvailableSensors, + pub null1: u8, + pub flight_mode: u32, + pub current_pid_profile_index: u8, + pub average_system_load_percent: u16, + pub max_profile_count: u8, + pub current_control_rate_profile_index: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspBfConfig { + pub mixer_configuration: u8, + pub features: u32, + pub serial_rx_provider: u8, + pub board_align_roll: i16, + pub board_align_pitch: i16, + pub board_align_yaw: i16, + pub current_scale: i16, + pub current_offset: i16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspRawImu { + pub acc_x: i16, + pub acc_y: i16, + pub acc_z: i16, + pub gyro_x: i16, + pub gyro_y: i16, + pub gyro_z: i16, + pub mag_x: i16, + pub mag_y: i16, + pub mag_z: i16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspDataFlashSummaryReply { + #[packed_field(bits = "6")] + pub supported: bool, + #[packed_field(bits = "7")] + pub ready: bool, + pub sectors: u32, + pub total_size_bytes: u32, + pub used_size_bytes: u32, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspDataFlashReply { + pub read_address: u32, + // pub payload: Vec, // TODO: packed_struct should support dynamic size too the end +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "6", endian = "lsb", bit_numbering = "msb0")] +pub struct MspDataFlashRead { + pub read_address: u32, + pub read_length: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspAccTrim { + pub pitch: u16, + pub roll: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspIdent { + pub version: u8, + pub mixer_mode: u8, + pub protocol_version: u8, + pub capability: u32, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspMisc { + pub rx_mid_rc: u16, + pub min_throttle: u16, + pub max_throttle: u16, + pub min_command: u16, + pub failsafe_throttle: u16, + + pub gps_type: u8, + pub gps_baudrate: u8, + pub gps_sbas_mode: u8, + + pub current_meter_output: u8, + pub rssi_channel: u8, + pub null1: u8, + + pub compass_mag_declination: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspAttitude { + pub roll: i16, + pub pitch: i16, + pub yaw: i16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspAltitude { + /// [centimeters] + pub altitude: i32, + /// variometer [cm/s] + pub vario: i16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspBatteryConfig { + pub vbat_min_cell_voltage: u8, + pub vbat_max_cell_voltage: u8, + pub vbat_warning_cell_voltage: u8, + pub battery_capacity: u16, + pub voltage_meter_source: u8, + pub current_meter_source: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspAnalog { + pub battery_voltage: u8, + pub mah_drawn: u16, + pub rssi: u16, + /// Current in 0.01A steps, range is -320A to 320A + pub amperage: i16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspRssiConfig { + pub rssi_channel: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspVoltageMeter { + pub id: u8, + pub value: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspCurrentMeter { + pub id: u8, + pub mah_drawn: u16, + /// In 0.001A steps (mA) + pub amperage: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspBatteryState { + pub battery_cell_count: u8, + /// mAh + pub battery_capacity: u16, + + pub battery_voltage: u8, + pub mah_drawn: u16, + /// 0.01A + pub amperage: i16, + + pub alerts: u8, +} + +impl MspBatteryState { + pub fn cell_voltage(&self) -> f32 { + self.battery_voltage as f32 / (10 * self.battery_cell_count) as f32 + } +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspRcTuning { + pub rc_rate8: u8, + pub rc_expo8: u8, + + pub rate_roll: u8, + pub rate_pitch: u8, + pub rate_yaw: u8, + + pub dyn_thr_pid: u8, + pub thr_mid8: u8, + pub thr_expo8: u8, + pub tpa_breakpoint: u16, + pub rc_yaw_expo8: u8, + pub rc_yaw_rate8: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspRxConfig { + pub serialrx_provider: u8, + pub maxcheck: u16, + pub midrc: u16, + pub mincheck: u16, + pub spektrum_sat_bind: u8, + pub rx_min_usec: u16, + pub rx_max_usec: u16, + pub rc_interpolation: u8, + pub rc_interpolation_interval: u8, + pub air_mode_activate_threshold: u16, + pub rx_spi_protocol: u8, + pub rx_spi_id: u32, + pub rx_spi_rf_channel_count: u8, + pub fpv_cam_angle_degrees: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspRcChannelValue { + pub value: u16, +} + +#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq)] +pub enum MspRcChannel { + /// Ailerons + Roll = 0, + /// Elevators + Pitch = 1, + /// Rudder + Yaw = 2, + Throttle = 3, + Aux1 = 4, + Aux2 = 5, + Aux3 = 6, + Aux4 = 7, + Aux5 = 8, + Aux6 = 9, + Aux7 = 10, + Aux8 = 11, + Aux9 = 12, + Aux10 = 13, + Aux11 = 14, + Aux12 = 15, + Aux13 = 16, + Aux14 = 17, + Aux15 = 18, + Aux16 = 19, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +pub struct MspRcMappedChannel { + #[packed_field(size_bits = "8", ty = "enum")] + pub channel: MspRcChannel, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +pub struct MspFeatures { + pub features: [bool; 32], +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspMotor { + pub motors: [u16; 8], +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspMotor3DConfig { + pub deadband_3d_low: u16, + pub deadband_3d_high: u16, + pub neutral_3d: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspMotorConfig { + pub min_throttle: u16, + pub max_throttle: u16, + pub min_command: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspRcDeadband { + pub deadband: u8, + pub yaw_deadband: u8, + pub alt_hold_deadband: u8, + pub deadband_3d_throttle: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspSensorAlignment { + pub gyro_alignment: u8, + pub acc_alignment: u8, + pub mag_alignment: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspAdvancedConfig { + pub gyro_sync_denom: u8, + pub pid_process_denom: u8, + pub use_unsynced_pwm: u8, + pub motor_pwm_protocol: u8, + pub motor_pwm_rate: u16, + pub digital_idle_offset_percent: u16, + pub gyro_use_32khz: u8, + pub motor_pwm_inversion: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspFilterConfig { + pub gyro_soft_lpf_hz: u8, + pub dterm_lpf_hz: u16, + pub yaw_lpf_hz: u16, + pub gyro_soft_notch_hz_1: u16, + pub gyro_soft_notch_cutoff_1: u16, + pub dterm_notch_hz: u16, + pub dterm_notch_cutoff: u16, + pub gyro_soft_notch_hz_2: u16, + pub gyro_soft_notch_cutoff_2: u16, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspPidAdvanced { + pub _r1: u16, + pub _r2: u16, + pub _r3: u16, + pub _r4: u8, + pub vbat_pid_compensation: u8, + pub setpoint_relax_ratio: u8, + pub dterm_setpoint_weight: u8, + pub _r5: u8, + pub _r6: u8, + pub _r7: u8, + pub rate_accel_limit: u16, + pub yaw_rate_accel_limit: u16, + pub level_angle_limit: u8, + pub level_sensitivity: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspSensorConfig { + pub acc_hardware: u8, + pub baro_hardware: u8, + pub mag_hardware: u8, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone, Default)] +#[packed_struct(endian = "lsb")] +pub struct MspServos { + pub servos: [u16; 8], +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "14", endian = "lsb", bit_numbering = "msb0")] +pub struct MspServoConfig { + pub min: u16, + pub max: u16, + pub middle: u16, + pub rate: i8, + pub unused1: u8, + pub unused2: u8, + pub forward_from_channel: u8, // Deprecated, set to 255 for backward compatibility + pub reverse_input: u32, // Deprecated, Input reversing is not required since it can be done on mixer level +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetServoConfig { + pub index: u8, + #[packed_field(size_bytes = "14")] + pub servo_config: MspServoConfig, +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspMixerConfig { + #[packed_field(size_bits = "8", ty = "enum")] + pub mixer_mode: MixerMode, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "4", endian = "lsb", bit_numbering = "msb0")] +pub struct MspModeRange { + pub box_id: u8, + #[packed_field(size_bits = "8", ty = "enum")] + pub aux_channel_index: MspRcChannel, + pub start_step: u8, + pub end_step: u8, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "5", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetModeRange { + pub index: u8, + #[packed_field(size_bytes = "4")] + pub mode_range: MspModeRange, +} + +#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq)] +pub enum MixerMode { + Tri = 1, + QuadPlus = 2, + QuadX = 3, + Bicopter = 4, + Gimbal = 5, + Y6 = 6, + Hex6 = 7, + FlyingWing = 8, + Y4 = 9, + Hex6X = 10, + OctoX8 = 11, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "8", endian = "lsb", bit_numbering = "msb0")] +pub struct MspMotorMixer { + pub throttle: u16, + pub roll: u16, + pub pitch: u16, + pub yaw: u16, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "9", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetMotorMixer { + pub index: u8, + #[packed_field(size_bytes = "8")] + pub motor_mixer: MspMotorMixer, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "13", endian = "lsb", bit_numbering = "msb0")] +pub struct MspOsdConfig { + pub video_system: u8, + pub units: u8, + pub rssi_alarm: u8, + pub capacity_warning: u16, + pub time_alarm: u16, + pub alt_alarm: u16, + pub dist_alarm: u16, + pub neg_alt_alarm: u16, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetGetOsdConfig { + pub item_index: u8, + #[packed_field(size_bytes = "13")] + pub config: MspOsdConfig, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "2", endian = "lsb", bit_numbering = "msb0")] +pub struct MspOsdItemPosition { + pub col: u8, + pub row: u8, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetOsdLayout { + pub item_index: u8, + #[packed_field(size_bytes = "2")] + pub item: MspOsdItemPosition, +} + +// inav msp layout item +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetOsdLayoutItem { + pub layout_index: u8, + #[packed_field(size_bytes = "3")] + pub item: MspSetOsdLayout, +} + +#[derive(Debug)] +pub struct MspOsdSettings { + pub osd_support: u8, + pub config: MspOsdConfig, + pub item_positions: Vec, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "2", endian = "lsb", bit_numbering = "msb0")] +pub struct MspOsdLayouts { + pub layout_count: u8, + pub item_count: u8, +} + +#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq)] +pub enum SerialIdentifier { + None = 255, + USART1 = 0, + USART2 = 1, + USART3 = 2, + USART4 = 3, + USART5 = 4, + USART6 = 5, + USART7 = 6, + USART8 = 7, + UsbVcp = 20, + SoftSerial1 = 30, + SoftSerial2 = 31, +} + +impl TryFrom for SerialIdentifier { + type Error = &'static str; + + fn try_from(value: u8) -> Result { + let serial = match value { + 255 => SerialIdentifier::None, + 0 => SerialIdentifier::USART1, + 1 => SerialIdentifier::USART2, + 2 => SerialIdentifier::USART3, + 3 => SerialIdentifier::USART4, + 4 => SerialIdentifier::USART5, + 5 => SerialIdentifier::USART6, + 6 => SerialIdentifier::USART7, + 7 => SerialIdentifier::USART8, + 20 => SerialIdentifier::UsbVcp, + 30 => SerialIdentifier::SoftSerial1, + 31 => SerialIdentifier::SoftSerial2, + _ => return Err("Serial identifier not found"), + }; + + Ok(serial) + } +} + +#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq)] +pub enum Baudrate { + BaudAuto = 0, + Baud1200 = 1, + Baud2400 = 2, + Baud4800 = 3, + Baud9600 = 4, + Baud19200 = 5, + Baud38400 = 6, + Baud57600 = 7, + Baud115200 = 8, + Baud230400 = 9, + Baud250000 = 10, + Baud460800 = 11, + Baud921600 = 12, + Baud1000000 = 13, + Baud1500000 = 14, + Baud2000000 = 15, + Baud2470000 = 16, +} + +impl TryFrom<&str> for Baudrate { + type Error = &'static str; + + fn try_from(value: &str) -> Result { + let baudrate = match value { + "0" => Baudrate::BaudAuto, + "1200" => Baudrate::Baud1200, + "2400" => Baudrate::Baud2400, + "4800" => Baudrate::Baud4800, + "9600" => Baudrate::Baud9600, + "19200" => Baudrate::Baud19200, + "38400" => Baudrate::Baud38400, + "57600" => Baudrate::Baud57600, + "115200" => Baudrate::Baud115200, + "230400" => Baudrate::Baud230400, + "250000" => Baudrate::Baud250000, + "460800" => Baudrate::Baud460800, + "921600" => Baudrate::Baud921600, + "1000000" => Baudrate::Baud1000000, + "1500000" => Baudrate::Baud1500000, + "2000000" => Baudrate::Baud2000000, + "2470000" => Baudrate::Baud2470000, + _ => return Err("Baudrate identifier not found"), + }; + + Ok(baudrate) + } +} + +impl From for String { + fn from(value: Baudrate) -> Self { + match value { + Baudrate::BaudAuto => "0", + Baudrate::Baud1200 => "1200", + Baudrate::Baud2400 => "2400", + Baudrate::Baud4800 => "4800", + Baudrate::Baud9600 => "9600", + Baudrate::Baud19200 => "19200", + Baudrate::Baud38400 => "38400", + Baudrate::Baud57600 => "57600", + Baudrate::Baud115200 => "115200", + Baudrate::Baud230400 => "230400", + Baudrate::Baud250000 => "250000", + Baudrate::Baud460800 => "460800", + Baudrate::Baud921600 => "921600", + Baudrate::Baud1000000 => "1000000", + Baudrate::Baud1500000 => "1500000", + Baudrate::Baud2000000 => "2000000", + Baudrate::Baud2470000 => "2470000", + } + .to_owned() + } +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb", bit_numbering = "msb0")] +pub struct MspSerialSetting { + #[packed_field(size_bits = "8", ty = "enum")] + pub identifier: SerialIdentifier, + pub function_mask: u32, + #[packed_field(size_bits = "8", ty = "enum")] + pub msp_baudrate_index: Baudrate, + #[packed_field(size_bits = "8", ty = "enum")] + pub gps_baudrate_index: Baudrate, + #[packed_field(size_bits = "8", ty = "enum")] + pub telemetry_baudrate_index: Baudrate, + #[packed_field(size_bits = "8", ty = "enum")] + pub peripheral_baudrate_index: Baudrate, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetServoMixRule { + pub index: u8, + #[packed_field(size_bytes = "8")] + pub servo_rule: MspServoMixRule, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "8", endian = "lsb", bit_numbering = "msb0")] +pub struct MspServoMixRule { + pub target_channel: u8, + pub input_source: u8, + pub rate: u16, + pub speed: u8, + pub min: u8, + pub max: u8, + pub box_id: u8, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "1", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSetServoMixer { + pub index: u8, + #[packed_field(size_bytes = "6")] + pub servo_rule: MspServoMixer, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "6", endian = "lsb", bit_numbering = "msb0")] +pub struct MspServoMixer { + pub target_channel: u8, + pub input_source: u8, + pub rate: i16, + pub speed: u8, + pub condition_id: i8, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb", bit_numbering = "msb0")] +pub struct MspRxMap { + pub map: [u8; 4], // MAX_MAPPABLE_RX_INPUTS +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb", bit_numbering = "msb0")] +pub struct MspSettingGroup { + pub group_id: u16, + pub start_id: u16, + pub end_id: u16, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb", bit_numbering = "msb0")] +pub struct MspSettingInfoRequest { + pub null: u8, + pub id: u16, +} + +#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq)] +pub enum SettingMode { + ModeDirect = 0, + ModeLookup = 0x40, +} + +#[derive(PrimitiveEnum, Serialize, Deserialize, Debug, Copy, Clone, PartialEq)] +pub enum SettingType { + VarUint8 = 0, + VarInt8, + VarUint16, + VarInt16, + VarUint32, + VarInt32, + VarFloat, + VarString, +} + +#[derive(PackedStruct, Debug, Copy, Clone)] +#[packed_struct(bytes = "15", endian = "lsb", bit_numbering = "msb0")] +pub struct MspSettingInfo { + // pub name: [u8; ?], null terminated strings + + // Parameter Group ID + pub group_id: u16, + + // Type, section and mode + #[packed_field(size_bits = "8", ty = "enum")] + pub setting_type: SettingType, + pub setting_section: u8, + #[packed_field(size_bits = "8", ty = "enum")] + pub setting_mode: SettingMode, + + pub min: u32, + pub max: u32, + + // Absolute setting index + pub absolute_index: u16, + + // If the setting is profile based, send the current one + // and the count, both as uint8_t. For MASTER_VALUE, we + // send two zeroes, so the MSP client can assume there + pub profile_id: u8, + pub profile_count: u8, + // if setting uses enum values, it will be written here + // pub enum_names: [String; ?] // TODO: packed_struct should support null terminated string parsing + // pub value: [u8; ?] +} + +#[derive(PackedStruct, Serialize, Deserialize, Debug, Copy, Clone)] +#[packed_struct(endian = "lsb")] +pub struct MspRc { + pub channels: [u16; 16], // 16 RC channels +} + +impl Default for MspRc { + fn default() -> Self { + Self::new() + } +} + +impl MspRc { + pub fn new() -> Self { + MspRc { channels: [0; 16] } + } + + pub fn set_roll(&mut self, value: u16) { + self.channels[0] = value; + } + + pub fn set_pitch(&mut self, value: u16) { + self.channels[1] = value; + } + + pub fn set_throttle(&mut self, value: u16) { + self.channels[2] = value; + } + + pub fn set_yaw(&mut self, value: u16) { + self.channels[3] = value; + } + + pub fn set_aux1(&mut self, value: u16) { + self.channels[4] = value; + } + pub fn set_aux2(&mut self, value: u16) { + self.channels[5] = value; + } + pub fn set_aux3(&mut self, value: u16) { + self.channels[6] = value; + } + pub fn set_aux4(&mut self, value: u16) { + self.channels[7] = value; + } +} + +#[test] +fn test_mixer() { + use packed_struct::prelude::*; + + let m = MspMixerConfig { + mixer_mode: MixerMode::QuadX, + }; + assert_eq!(3, m.mixer_mode.to_primitive()); + let r = m.pack().unwrap(); + assert_eq!(3, r.as_slice()[0]); +}