pub struct Altitude {
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,
}Expand description
MAVLink ALTITUDE message.
The minimum supported MAVLink version is MAVLink 1.
§Description
The current system altitude.
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
Altitude (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§time_usec: u64MAVLink field time_usec.
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: f32MAVLink field altitude_monotonic.
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: f32MAVLink field altitude_amsl.
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: f32MAVLink field altitude_local.
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: f32MAVLink field altitude_relative.
This is the altitude above the home position. It resets on each change of the current home position.
altitude_terrain: f32MAVLink field altitude_terrain.
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: f32MAVLink field bottom_clearance.
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§
Source§impl Altitude
impl Altitude
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> u32
pub const fn message_id() -> u32
Message ID.
Sourcepub const fn min_supported_mavlink_version() -> MavLinkVersion
pub const fn min_supported_mavlink_version() -> MavLinkVersion
Minimum supported MAVLink version for this message.
Trait Implementations§
Source§impl<'de> Deserialize<'de> for Altitude
impl<'de> Deserialize<'de> for Altitude
Source§fn deserialize<__D>(
__deserializer: __D,
) -> Result<Altitude, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(
__deserializer: __D,
) -> Result<Altitude, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
Source§impl IntoPayload for Altitude
impl IntoPayload for Altitude
Source§impl MessageSpec for Altitude
impl MessageSpec for Altitude
Source§impl MessageSpecStatic for Altitude
impl MessageSpecStatic for Altitude
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> u32
fn message_id() -> u32
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for Altitude
impl NamedType for Altitude
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl Serialize for Altitude
impl Serialize for Altitude
Source§fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
Source§impl Type for Altitude
impl Type for Altitude
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.