pub type MessageId = u32;
pub type CrcExtra = u8;
pub type DialectId = u32;
pub type DialectVersion = u8;
#[derive(Clone, Copy, Debug, Default, PartialEq, Eq)]
#[cfg_attr(feature = "specta", derive(specta::Type))]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub enum MavLinkVersion {
V1,
#[default]
V2,
}
pub type SystemId = u8;
pub type ComponentId = u8;
#[derive(Copy, Clone, Debug, Eq, PartialEq, Hash)]
#[cfg_attr(feature = "specta", derive(specta::Type))]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct MavLinkId {
pub system: SystemId,
pub component: ComponentId,
}
impl MavLinkId {
pub fn new(system: SystemId, component: ComponentId) -> Self {
Self { system, component }
}
}