diff --git a/Cargo.toml b/Cargo.toml index b7acf38..a1e81f8 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,2 +1,3 @@ [workspace] members = ["ublox", "ublox_derive"] +resolver = "2" diff --git a/examples/Cargo.toml b/examples/Cargo.toml index 748801c..9843613 100644 --- a/examples/Cargo.toml +++ b/examples/Cargo.toml @@ -1,3 +1,4 @@ [workspace] exclude = ["target"] members = ["*"] +resolver = "2" diff --git a/examples/basic-cli/Cargo.toml b/examples/basic-cli/Cargo.toml index 7081ab2..1ae807f 100644 --- a/examples/basic-cli/Cargo.toml +++ b/examples/basic-cli/Cargo.toml @@ -1,8 +1,9 @@ [package] -authors = ["Lane Kolbly ", "Andrei Gherghescu "] +authors = ["Lane Kolbly ", "Andrei Gherghescu "] edition = "2021" name = "basic-cli" publish = false +rust-version = "1.70" version = "0.1.0" [dependencies] diff --git a/examples/basic-cli/src/main.rs b/examples/basic-cli/src/main.rs index 318880b..bea0785 100644 --- a/examples/basic-cli/src/main.rs +++ b/examples/basic-cli/src/main.rs @@ -27,13 +27,14 @@ fn main() { .short('s') .long("baud") .required(false) + .default_value("9600") .value_parser(value_parser!(u32)) - .help("Baud rate of the port"), + .help("Baud rate of the port to open"), ) .arg( Arg::new("stop-bits") .long("stop-bits") - .help("Number of stop bits to use") + .help("Number of stop bits to use for opened port") .required(false) .value_parser(["1", "2"]) .default_value("1"), @@ -41,33 +42,148 @@ fn main() { .arg( Arg::new("data-bits") .long("data-bits") - .help("Number of data bits to use") + .help("Number of data bits to use for opened port") .required(false) - .value_parser(["5", "6", "7", "8"]) + .value_parser(["7", "8"]) .default_value("8"), ) + .arg( + Arg::new("parity") + .long("parity") + .help("Parity to use for open port") + .required(false) + .value_parser(["even", "odd"]), + ) + .subcommand( + Command::new("configure") + .about("Configure settings for specific UART/USB port") + .arg( + Arg::new("port") + .long("select") + .required(true) + .default_value("usb") + .value_parser(value_parser!(String)) + .long_help( + "Apply specific configuration to the selected port. Supported: usb, uart1, uart2. +Configuration includes: protocol in/out, data-bits, stop-bits, parity, baud-rate", + ), + ) + .arg( + Arg::new("cfg-baud") + .value_name("baud") + .long("baud") + .required(false) + .default_value("9600") + .value_parser(value_parser!(u32)) + .help("Baud rate to set"), + ) + .arg( + Arg::new("stop-bits") + .long("stop-bits") + .help("Number of stop bits to set") + .required(false) + .value_parser(["1", "2"]) + .default_value("1"), + ) + .arg( + Arg::new("data-bits") + .long("data-bits") + .help("Number of data bits to set") + .required(false) + .value_parser(["7", "8"]) + .default_value("8"), + ) + .arg( + Arg::new("parity") + .long("parity") + .help("Parity to set") + .required(false) + .value_parser(["even", "odd"]), + ) + .arg( + Arg::new("in-ublox") + .long("in-ublox") + .default_value("true") + .action(clap::ArgAction::SetTrue) + .help("Toggle receiving UBX proprietary protocol on port"), + ) + .arg( + Arg::new("in-nmea") + .long("in-nmea") + .default_value("false") + .action(clap::ArgAction::SetTrue) + .help("Toggle receiving NMEA protocol on port"), + ) + .arg( + Arg::new("in-rtcm") + .long("in-rtcm") + .default_value("false") + .action(clap::ArgAction::SetTrue) + .help("Toggle receiving RTCM protocol on port"), + ) + .arg( + Arg::new("in-rtcm3") + .long("in-rtcm3") + .default_value("false") + .action(clap::ArgAction::SetTrue) + .help( + "Toggle receiving RTCM3 protocol on port. + Not supported on uBlox protocol versions below 20", + ), + ) + .arg( + Arg::new("out-ublox") + .long("out-ublox") + .action(clap::ArgAction::SetTrue) + .help("Toggle sending UBX proprietary protocol on port"), + ) + .arg( + Arg::new("out-nmea") + .long("out-nmea") + .action(clap::ArgAction::SetTrue) + .help("Toggle sending NMEA protocol on port"), + ) + .arg( + Arg::new("out-rtcm3") + .long("out-rtcm3") + .action(clap::ArgAction::SetTrue) + .help( + "Toggle seding RTCM3 protocol on port. + Not supported on uBlox protocol versions below 20", + ), + ), + ) .get_matches(); let port = matches .get_one::("port") .expect("Expected required 'port' cli argumnet"); + let baud = matches.get_one::("baud").cloned().unwrap_or(9600); let stop_bits = match matches.get_one::("stop-bits").map(|s| s.as_str()) { Some("2") => SerialStopBits::Two, _ => SerialStopBits::One, }; let data_bits = match matches.get_one::("data-bits").map(|s| s.as_str()) { - Some("5") => SerialDataBits::Five, - Some("6") => SerialDataBits::Six, Some("7") => SerialDataBits::Seven, - _ => SerialDataBits::Eight, + Some("8") => SerialDataBits::Eight, + _ => { + println!("Number of DataBits supported by uBlox is either 7 or 8"); + std::process::exit(1); + }, + }; + + let parity = match matches.get_one::("parity").map(|s| s.as_str()) { + Some("odd") => SerialParity::Even, + Some("even") => SerialParity::Odd, + _ => SerialParity::None, }; let builder = serialport::new(port, baud) .stop_bits(stop_bits) .data_bits(data_bits) - .timeout(Duration::from_millis(1)) - .parity(SerialParity::None) + .timeout(Duration::from_millis(10)) + .parity(parity) .flow_control(SerialFlowControl::None); println!("{:?}", &builder); @@ -75,20 +191,111 @@ fn main() { eprintln!("Failed to open \"{}\". Error: {}", port, e); ::std::process::exit(1); }); + let mut device = Device::new(port); - // Configure the device to talk UBX - println!("Configuring UART1 port ..."); + // Parse cli for configuring specific uBlox UART port + if let Some(("configure", sub_matches)) = matches.subcommand() { + let (port_id, port_name) = match sub_matches.get_one::("port").map(|s| s.as_str()) { + Some(x) if x == "usb" => (Some(UartPortId::Usb), x), + Some(x) if x == "uart1" => (Some(UartPortId::Uart1), x), + Some(x) if x == "uart2" => (Some(UartPortId::Uart2), x), + _ => (None, ""), + }; + + let baud = sub_matches.get_one::("baud").cloned().unwrap_or(9600); + + let stop_bits = match sub_matches + .get_one::("stop-bits") + .map(|s| s.as_str()) + { + Some("2") => SerialStopBits::Two, + _ => SerialStopBits::One, + }; + + let data_bits = match sub_matches + .get_one::("data-bits") + .map(|s| s.as_str()) + { + Some("7") => SerialDataBits::Seven, + Some("8") => SerialDataBits::Eight, + _ => { + println!("Number of DataBits supported by uBlox is either 7 or 8"); + std::process::exit(1); + }, + }; + + let parity = match sub_matches.get_one::("parity").map(|s| s.as_str()) { + Some("odd") => SerialParity::Even, + Some("even") => SerialParity::Odd, + _ => SerialParity::None, + }; + let inproto = match ( + sub_matches.get_flag("in-ublox"), + sub_matches.get_flag("in-nmea"), + sub_matches.get_flag("in-rtcm"), + sub_matches.get_flag("in-rtcm3"), + ) { + (true, false, false, false) => InProtoMask::UBLOX, + (false, true, false, false) => InProtoMask::NMEA, + (false, false, true, false) => InProtoMask::RTCM, + (false, false, false, true) => InProtoMask::RTCM3, + (true, true, false, false) => InProtoMask::union(InProtoMask::UBLOX, InProtoMask::NMEA), + (true, false, true, false) => InProtoMask::union(InProtoMask::UBLOX, InProtoMask::RTCM), + (true, false, false, true) => { + InProtoMask::union(InProtoMask::UBLOX, InProtoMask::RTCM3) + }, + (false, true, true, false) => InProtoMask::union(InProtoMask::NMEA, InProtoMask::RTCM), + (false, true, false, true) => InProtoMask::union(InProtoMask::NMEA, InProtoMask::RTCM3), + (true, true, true, false) => InProtoMask::union( + InProtoMask::union(InProtoMask::UBLOX, InProtoMask::NMEA), + InProtoMask::RTCM, + ), + (true, true, false, true) => InProtoMask::union( + InProtoMask::union(InProtoMask::UBLOX, InProtoMask::NMEA), + InProtoMask::RTCM3, + ), + (_, _, true, true) => { + eprintln!("Cannot use RTCM and RTCM3 simultaneously. Choose one or the other"); + std::process::exit(1) + }, + (false, false, false, false) => InProtoMask::UBLOX, + }; + + let outproto = match ( + sub_matches.get_flag("out-ublox"), + sub_matches.get_flag("out-nmea"), + sub_matches.get_flag("out-rtcm3"), + ) { + (true, false, false) => OutProtoMask::UBLOX, + (false, true, false) => OutProtoMask::NMEA, + (false, false, true) => OutProtoMask::RTCM3, + (true, true, false) => OutProtoMask::union(OutProtoMask::UBLOX, OutProtoMask::NMEA), + (true, false, true) => OutProtoMask::union(OutProtoMask::UBLOX, OutProtoMask::RTCM3), + (false, true, true) => OutProtoMask::union(OutProtoMask::NMEA, OutProtoMask::RTCM3), + (true, true, true) => OutProtoMask::union( + OutProtoMask::union(OutProtoMask::UBLOX, OutProtoMask::NMEA), + OutProtoMask::RTCM3, + ), + (false, false, false) => OutProtoMask::UBLOX, + }; + + if let Some(port_id) = port_id { + println!("Configuring '{}' port ...", port_name.to_uppercase()); device .write_all( &CfgPrtUartBuilder { - portid: UartPortId::Uart1, + portid: port_id, reserved0: 0, tx_ready: 0, - mode: UartMode::new(DataBits::Eight, Parity::None, StopBits::One), + mode: UartMode::new( + ublox_databits(data_bits), + ublox_parity(parity), + ublox_stopbits(stop_bits), + ), baud_rate: baud, - in_proto_mask: InProtoMask::UBLOX, - out_proto_mask: OutProtoMask::union(OutProtoMask::NMEA, OutProtoMask::UBLOX), + in_proto_mask: inproto, + out_proto_mask: outproto, flags: 0, reserved5: 0, } @@ -98,11 +305,16 @@ fn main() { device .wait_for_ack::() .expect("Could not acknowledge UBX-CFG-PRT-UART msg"); + } + } // Enable the NavPvt packet + // By setting 1 in the array below, we enable the NavPvt message for Uart1, Uart2 and USB + // The other positions are for I2C, SPI, etc. Consult your device manual. + println!("Enable UBX-NAV-PVT message on all serial ports: USB, UART1 and UART2 ..."); device .write_all( - &CfgMsgAllPortsBuilder::set_rate_for::([0, 1, 0, 0, 0, 0]).into_packet_bytes(), + &CfgMsgAllPortsBuilder::set_rate_for::([0, 1, 1, 1, 0, 0]).into_packet_bytes(), ) .expect("Could not configure ports for UBX-NAV-PVT"); device @@ -164,6 +376,33 @@ fn main() { } } +fn ublox_stopbits(s: SerialStopBits) -> StopBits { + // Seriaport crate doesn't support the other StopBits option of uBlox + match s { + SerialStopBits::One => StopBits::One, + SerialStopBits::Two => StopBits::Two, + } +} + +fn ublox_databits(d: SerialDataBits) -> DataBits { + match d { + SerialDataBits::Seven => DataBits::Seven, + SerialDataBits::Eight => DataBits::Eight, + _ => { + println!("uBlox only supports Seven or Eight data bits"); + DataBits::Eight + }, + } +} + +fn ublox_parity(v: SerialParity) -> Parity { + match v { + SerialParity::Even => Parity::Even, + SerialParity::Odd => Parity::Odd, + SerialParity::None => Parity::None, + } +} + struct Device { port: Box, parser: Parser>, diff --git a/ublox/Cargo.toml b/ublox/Cargo.toml index e25195d..e80cc02 100644 --- a/ublox/Cargo.toml +++ b/ublox/Cargo.toml @@ -7,7 +7,7 @@ name = "ublox" publish = false readme = "../README.md" repository = "https://github.com/lkolbly/ublox" -version = "0.4.2" +version = "0.4.5" [features] alloc = [] @@ -19,7 +19,7 @@ bitflags = "2.3.1" chrono = {version = "0.4.19", default-features = false, features = []} num-traits = {version = "0.2.12", default-features = false} serde = {version = "1.0.144", optional = true, default-features = false, features = ["derive"]} -ublox_derive = {path = "../ublox_derive", version = "0.0.4"} +ublox_derive = {path = "../ublox_derive", version = "=0.1.0"} [dev-dependencies] cpu-time = "1.0.0" diff --git a/ublox/src/lib.rs b/ublox/src/lib.rs index b6c3b37..fb7a6c3 100644 --- a/ublox/src/lib.rs +++ b/ublox/src/lib.rs @@ -2,7 +2,8 @@ //! //! This project aims to build a pure-rust I/O library for ublox GPS devices, specifically using the UBX protocol. //! -//! An example of using this library to talk to a device can be seen in the examples subfolder of this project. +//! An example of using this library to talk to a device can be seen in the examples/basic-cli subfolder of this project. +//! More examples are available in the examples subfolder. //! //! Constructing Packets //! ==================== diff --git a/ublox/src/ubx_packets/packets.rs b/ublox/src/ubx_packets/packets.rs index 4bf5099..db89e3a 100644 --- a/ublox/src/ubx_packets/packets.rs +++ b/ublox/src/ubx_packets/packets.rs @@ -25,6 +25,15 @@ use super::{ UbxUnknownPacketRef, SYNC_CHAR_1, SYNC_CHAR_2, }; +/// Used to help serialize the packet's fields flattened within a struct containing the msg_id and class fields, but +/// without using the serde FlatMapSerializer which requires alloc. +#[cfg(feature = "serde")] +pub(crate) trait SerializeUbxPacketFields { + fn serialize_fields(&self, serializer: &mut S) -> Result<(), S::Error> + where + S: serde::ser::SerializeMap; +} + /// Geodetic Position Solution #[ubx_packet_recv] #[ubx(class = 1, id = 2, fixed_payload_len = 28)] @@ -158,6 +167,66 @@ struct NavHpPosLlh { vertical_accuracy: u32, } +#[ubx_extend_bitflags] +#[ubx(from, into_raw, rest_reserved)] +bitflags! { + #[derive(Default, Debug)] + pub struct NavHpPosEcefFlags: u8 { + const INVALID_ECEF = 1; + + } +} + +/// High Precision Geodetic Position Solution (ECEF) +#[ubx_packet_recv] +#[ubx(class = 0x01, id = 0x13, fixed_payload_len = 28)] +struct NavHpPosEcef { + /// Message version (0 for protocol version 27) + version: u8, + + reserved1: [u8; 3], + + /// GPS Millisecond Time of Week + itow: u32, + + /// ECEF X coordinate + #[ubx(map_type = f64, alias = ecef_x_cm)] + ecef_x: i32, + + /// ECEF Y coordinate + #[ubx(map_type = f64, alias = ecef_y_cm)] + ecef_y: i32, + + /// ECEF Z coordinate + #[ubx(map_type = f64, alias = ecef_z_cm)] + ecef_z: i32, + + /// High precision component of X + /// Must be in the range -99..+99 + /// Precise coordinate in cm = ecef_x + (ecef_x_hp * 1e-2). + #[ubx(map_type = f64, scale = 1e-1, alias = ecef_x_hp_mm)] + ecef_x_hp: i8, + + /// High precision component of Y + /// Must be in the range -99..+99 + /// 9. Precise coordinate in cm = ecef_y + (ecef_y_hp * 1e-2). + #[ubx(map_type = f64, scale = 1e-1, alias = ecef_y_hp_mm)] + ecef_y_hp: i8, + + /// High precision component of Z + /// Must be in the range -99..+99 + /// Precise coordinate in cm = ecef_z + (ecef_z_hp * 1e-2). + #[ubx(map_type = f64, scale = 1e-1, alias = ecef_z_hp_mm)] + ecef_z_hp: i8, + + #[ubx(map_type = NavHpPosEcefFlags)] + flags: u8, + + /// Horizontal accuracy estimate (mm) + #[ubx(map_type = f64, scale = 1e-1)] + p_acc: u32, +} + /// Navigation Position Velocity Time Solution #[ubx_packet_recv] #[ubx(class = 1, id = 0x07, fixed_payload_len = 92)] @@ -4120,6 +4189,7 @@ define_recv_packets!( NavSolution, NavVelNed, NavHpPosLlh, + NavHpPosEcef, NavTimeUTC, NavTimeLs, NavSat, diff --git a/ublox/src/ubx_packets/types.rs b/ublox/src/ubx_packets/types.rs index d8988cb..4b93b7d 100644 --- a/ublox/src/ubx_packets/types.rs +++ b/ublox/src/ubx_packets/types.rs @@ -17,6 +17,20 @@ pub struct Position { pub alt: f64, } +/// Represents a world position in the ECEF coordinate system +#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))] +#[derive(Debug, Clone, Copy)] +pub struct PositionECEF { + /// x coordinates in meters + pub x: f64, + + /// y coordinates in meters + pub y: f64, + + /// z coordinates in meters + pub z: f64, +} + #[derive(Debug, Clone, Copy)] #[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))] pub struct Velocity { @@ -47,6 +61,16 @@ impl<'a> From<&NavHpPosLlhRef<'a>> for Position { } } +impl<'a> From<&NavHpPosEcefRef<'a>> for PositionECEF { + fn from(packet: &NavHpPosEcefRef<'a>) -> Self { + PositionECEF { + x: 10e-2 * (packet.ecef_x_cm() + 0.1 * packet.ecef_x_hp_mm()), + y: 10e-2 * (packet.ecef_y_cm() + 0.1 * packet.ecef_y_hp_mm()), + z: 10e-2 * (packet.ecef_z_cm() + 0.1 * packet.ecef_z_hp_mm()), + } + } +} + impl<'a> From<&NavVelNedRef<'a>> for Velocity { fn from(packet: &NavVelNedRef<'a>) -> Self { Velocity { diff --git a/ublox/tests/parser_tests.rs b/ublox/tests/parser_tests.rs index 067cacd..2b9785f 100644 --- a/ublox/tests/parser_tests.rs +++ b/ublox/tests/parser_tests.rs @@ -279,7 +279,7 @@ fn test_double_start_at_end() { 0xb5, 0x62, 0x05, 0x01, 0x00, 0x00, 0x06, 0x17, // Zero-sized packet ]; - let mut buf = vec![0; 10]; + let mut buf = [0; 10]; let buf = ublox::FixedLinearBuffer::new(&mut buf[..]); let mut parser = ublox::Parser::new(buf); diff --git a/ublox_derive/Cargo.toml b/ublox_derive/Cargo.toml index 7aa2b5b..91c2ad1 100644 --- a/ublox_derive/Cargo.toml +++ b/ublox_derive/Cargo.toml @@ -5,7 +5,7 @@ edition = "2021" license = "MIT" name = "ublox_derive" publish = false -version = "0.0.4" +version = "0.1.0" [lib] proc-macro = true diff --git a/ublox_derive/src/input.rs b/ublox_derive/src/input.rs index 28df6cb..1a1aa63 100644 --- a/ublox_derive/src/input.rs +++ b/ublox_derive/src/input.rs @@ -546,6 +546,7 @@ impl Parse for PackFieldMap { } } +#[allow(dead_code)] struct Comment(String); impl Parse for Comment { diff --git a/ublox_derive/src/output.rs b/ublox_derive/src/output.rs index cc9a724..7e1ba73 100644 --- a/ublox_derive/src/output.rs +++ b/ublox_derive/src/output.rs @@ -49,6 +49,17 @@ fn generate_serialize_impl( } }); quote! { + #[cfg(feature = "serde")] + impl SerializeUbxPacketFields for #ref_name<'_> { + fn serialize_fields(&self, state: &mut S) -> Result<(), S::Error> + where + S: serde::ser::SerializeMap, + { + #(#fields)* + Ok(()) + } + } + #[cfg(feature = "serde")] impl serde::Serialize for #ref_name<'_> { fn serialize(&self, serializer: S) -> Result @@ -56,7 +67,7 @@ fn generate_serialize_impl( S: serde::Serializer, { let mut state = serializer.serialize_map(None)?; - #(#fields)* + self.serialize_fields(&mut state)?; state.end() } } @@ -776,14 +787,27 @@ pub fn generate_code_for_parse(recv_packs: &RecvPackets) -> TokenStream { [a, b][(a < b) as usize] } pub(crate) const MAX_PAYLOAD_LEN: u16 = #max_payload_len_calc; - #[cfg_attr(feature = "serde", derive(serde::Serialize))] + #[cfg(feature = "serde")] pub struct PacketSerializer<'a, T> { class: u8, msg_id: u8, - #[cfg_attr(feature = "serde", serde(flatten))] msg: &'a T, } + #[cfg(feature = "serde")] + impl<'a, T: SerializeUbxPacketFields> serde::Serialize for PacketSerializer<'a, T> { + fn serialize(&self, serializer: S) -> Result + where + S: serde::Serializer, + { + let mut state = serializer.serialize_map(None)?; + state.serialize_entry("class", &self.class)?; + state.serialize_entry("msg_id", &self.msg_id)?; + self.msg.serialize_fields(&mut state)?; + state.end() + } + } + #[cfg(feature = "serde")] impl serde::Serialize for #union_enum_name<'_> { fn serialize(&self, serializer: S) -> Result diff --git a/ublox_derive/src/tests.rs b/ublox_derive/src/tests.rs index a431d57..1f01048 100644 --- a/ublox_derive/src/tests.rs +++ b/ublox_derive/src/tests.rs @@ -172,18 +172,28 @@ fn test_ubx_packet_recv_simple() { } } #[cfg(feature = "serde")] - impl serde::Serialize for TestRef<'_> { - fn serialize(&self, serializer: S) -> Result + impl SerializeUbxPacketFields for TestRef<'_> { + fn serialize_fields(&self, state: &mut S) -> Result<(), S::Error> where - S: serde::Serializer, + S: serde::ser::SerializeMap, { - let mut state = serializer.serialize_map(None)?; state.serialize_entry(stringify!(itow), &self.itow())?; state.serialize_entry(stringify!(lat), &self.lat_degrees())?; state.serialize_entry(stringify!(a), &self.a())?; state.serialize_entry(stringify!(reserved1), &self.reserved1())?; state.serialize_entry(stringify!(flags), &self.flags())?; state.serialize_entry(stringify!(b), &self.b())?; + Ok(()) + } + } + #[cfg(feature = "serde")] + impl serde::Serialize for TestRef<'_> { + fn serialize(&self, serializer: S) -> Result + where + S: serde::Serializer, + { + let mut state = serializer.serialize_map(None)?; + self.serialize_fields(&mut state)?; state.end() } } @@ -280,17 +290,27 @@ fn test_ubx_packet_recv_dyn_len() { } } #[cfg(feature = "serde")] - impl serde::Serialize for TestRef<'_> { - fn serialize(&self, serializer: S) -> Result + impl SerializeUbxPacketFields for TestRef<'_> { + fn serialize_fields(&self, state: &mut S) -> Result<(), S::Error> where - S: serde::Serializer, + S: serde::ser::SerializeMap, { - let mut state = serializer.serialize_map(None)?; state.serialize_entry(stringify!(f1), &self.f1())?; state.serialize_entry( stringify!(rest), &crate::ubx_packets::FieldIter(self.rest()), )?; + Ok(()) + } + } + #[cfg(feature = "serde")] + impl serde::Serialize for TestRef<'_> { + fn serialize(&self, serializer: S) -> Result + where + S: serde::Serializer, + { + let mut state = serializer.serialize_map(None)?; + self.serialize_fields(&mut state)?; state.end() } } @@ -556,14 +576,27 @@ fn test_define_recv_packets() { max_u16(Pack1::MAX_PAYLOAD_LEN, 0u16), ); - #[cfg_attr(feature = "serde", derive(serde :: Serialize))] + #[cfg(feature = "serde")] pub struct PacketSerializer<'a, T> { class: u8, msg_id: u8, - #[cfg_attr(feature = "serde", serde(flatten))] msg: &'a T, } + #[cfg(feature = "serde")] + impl<'a, T: SerializeUbxPacketFields> serde::Serialize for PacketSerializer<'a, T> { + fn serialize(&self, serializer: S) -> Result + where + S: serde::Serializer, + { + let mut state = serializer.serialize_map(None)?; + state.serialize_entry("class", &self.class)?; + state.serialize_entry("msg_id", &self.msg_id)?; + self.msg.serialize_fields(&mut state)?; + state.end() + } + } + #[cfg(feature = "serde")] impl serde::Serialize for PacketRef<'_> { fn serialize(&self, serializer: S) -> Result