pub struct UAVIONIX_ADSB_OUT_CFG_DATA {
    pub ICAO: u32,
    pub stallSpeed: u16,
    pub callsign: [u8; 9],
    pub emitterType: AdsbEmitterType,
    pub aircraftSize: UavionixAdsbOutCfgAircraftSize,
    pub gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat,
    pub gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon,
    pub rfSelect: UavionixAdsbOutRfSelect,
}
Expand description

id: 10001 Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter).

Fields§

§ICAO: u32

Vehicle address (24 bit).

§stallSpeed: u16

Aircraft stall speed in cm/s.

§callsign: [u8; 9]

Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, “ “ only).

§emitterType: AdsbEmitterType

Transmitting vehicle type. See ADSB_EMITTER_TYPE enum.

§aircraftSize: UavionixAdsbOutCfgAircraftSize

Aircraft length and width encoding (table 2-35 of DO-282B).

§gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat

GPS antenna lateral offset (table 2-36 of DO-282B).

§gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon

GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B).

§rfSelect: UavionixAdsbOutRfSelect

ADS-B transponder receiver and transmit enable flags.

Implementations§

source§

impl UAVIONIX_ADSB_OUT_CFG_DATA

source

pub const ENCODED_LEN: usize = 20usize

source

pub const DEFAULT: Self = _

Trait Implementations§

source§

impl Clone for UAVIONIX_ADSB_OUT_CFG_DATA

source§

fn clone(&self) -> UAVIONIX_ADSB_OUT_CFG_DATA

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl Debug for UAVIONIX_ADSB_OUT_CFG_DATA

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl Default for UAVIONIX_ADSB_OUT_CFG_DATA

source§

fn default() -> Self

Returns the “default value” for a type. Read more
source§

impl<'de> Deserialize<'de> for UAVIONIX_ADSB_OUT_CFG_DATA

source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
source§

impl MessageData for UAVIONIX_ADSB_OUT_CFG_DATA

§

type Message = MavMessage

source§

const ID: u32 = 10_001u32

source§

const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG"

source§

const EXTRA_CRC: u8 = 209u8

source§

const ENCODED_LEN: usize = 20usize

source§

fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>

source§

fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize

source§

impl PartialEq for UAVIONIX_ADSB_OUT_CFG_DATA

source§

fn eq(&self, other: &UAVIONIX_ADSB_OUT_CFG_DATA) -> bool

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

fn ne(&self, other: &Rhs) -> bool

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl Serialize for UAVIONIX_ADSB_OUT_CFG_DATA

source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
source§

impl StructuralPartialEq for UAVIONIX_ADSB_OUT_CFG_DATA

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for Twhere T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T, U> Into<U> for Twhere U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T> ToOwned for Twhere T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
source§

impl<T, U> TryFrom<U> for Twhere U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for Twhere U: TryFrom<T>,

§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<T> DeserializeOwned for Twhere T: for<'de> Deserialize<'de>,