pub struct UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
Show 16 fields pub utcTime: u32, pub gpsLat: i32, pub gpsLon: i32, pub gpsAlt: i32, pub baroAltMSL: i32, pub accuracyHor: u32, pub accuracyVert: u16, pub accuracyVel: u16, pub velVert: i16, pub velNS: i16, pub VelEW: i16, pub state: UavionixAdsbOutDynamicState, pub squawk: u16, pub gpsFix: UavionixAdsbOutDynamicGpsFix, pub numSats: u8, pub emergencyStatus: UavionixAdsbEmergencyStatus,
}
Expand description

id: 10002 Dynamic data used to generate ADS-B out transponder data (send at 5Hz).

Fields§

§utcTime: u32

UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX.

§gpsLat: i32

Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX.

§gpsLon: i32

Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX.

§gpsAlt: i32

Altitude (WGS84). UP +ve. If unknown set to INT32_MAX.

§baroAltMSL: i32

Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX.

§accuracyHor: u32

Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX.

§accuracyVert: u16

Vertical accuracy in cm. If unknown set to UINT16_MAX.

§accuracyVel: u16

Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX.

§velVert: i16

GPS vertical speed in cm/s. If unknown set to INT16_MAX.

§velNS: i16

North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX.

§VelEW: i16

East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX.

§state: UavionixAdsbOutDynamicState

ADS-B transponder dynamic input state flags.

§squawk: u16

Mode A code (typically 1200 [0x04B0] for VFR).

§gpsFix: UavionixAdsbOutDynamicGpsFix

0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK.

§numSats: u8

Number of satellites visible. If unknown set to UINT8_MAX.

§emergencyStatus: UavionixAdsbEmergencyStatus

Emergency status.

Implementations§

Trait Implementations§

source§

impl Clone for UAVIONIX_ADSB_OUT_DYNAMIC_DATA

source§

fn clone(&self) -> UAVIONIX_ADSB_OUT_DYNAMIC_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_DYNAMIC_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_DYNAMIC_DATA

source§

fn default() -> Self

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

impl<'de> Deserialize<'de> for UAVIONIX_ADSB_OUT_DYNAMIC_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_DYNAMIC_DATA

§

type Message = MavMessage

source§

const ID: u32 = 10_002u32

source§

const NAME: &'static str = "UAVIONIX_ADSB_OUT_DYNAMIC"

source§

const EXTRA_CRC: u8 = 186u8

source§

const ENCODED_LEN: usize = 41usize

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_DYNAMIC_DATA

source§

fn eq(&self, other: &UAVIONIX_ADSB_OUT_DYNAMIC_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_DYNAMIC_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_DYNAMIC_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>,