[][src]Struct mavlink::common::ALTITUDE_DATA

pub struct ALTITUDE_DATA {
    pub time_usec: u64,
    pub altitude_monotonic: f32,
    pub altitude_amsl: f32,
    pub altitude_local: f32,
    pub altitude_relative: f32,
    pub altitude_terrain: f32,
    pub bottom_clearance: f32,
}

id: 141 The current system altitude..

Fields

time_usec: u64

Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number..

altitude_monotonic: f32

This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights..

altitude_amsl: f32

This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is not the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude..

altitude_local: f32

This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive..

altitude_relative: f32

This is the altitude above the home position. It resets on each change of the current home position..

altitude_terrain: f32

This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown..

bottom_clearance: f32

This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available..

Implementations

impl ALTITUDE_DATA[src]

pub const ENCODED_LEN: usize[src]

pub fn deser(
    version: MavlinkVersion,
    _input: &[u8]
) -> Result<Self, ParserError>
[src]

pub fn ser(&self) -> Vec<u8>[src]

Trait Implementations

impl Clone for ALTITUDE_DATA[src]

impl Debug for ALTITUDE_DATA[src]

impl Default for ALTITUDE_DATA[src]

impl<'de> Deserialize<'de> for ALTITUDE_DATA[src]

impl PartialEq<ALTITUDE_DATA> for ALTITUDE_DATA[src]

impl Serialize for ALTITUDE_DATA[src]

impl StructuralPartialEq for ALTITUDE_DATA[src]

Auto Trait Implementations

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> DeserializeOwned for T where
    T: for<'de> Deserialize<'de>, 
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> ToOwned for T where
    T: Clone
[src]

type Owned = T

The resulting type after obtaining ownership.

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

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

The type returned in the event of a conversion error.