pub struct GlobalPositionIntCov {
pub time_usec: u64,
pub estimator_type: MavEstimatorType,
pub lat: i32,
pub lon: i32,
pub alt: i32,
pub relative_alt: i32,
pub vx: f32,
pub vy: f32,
pub vz: f32,
pub covariance: [f32; 36],
}Expand description
MAVLink GLOBAL_POSITION_INT_COV message.
The minimum supported MAVLink version is MAVLink 1.
§Description
The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset.
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
GlobalPositionIntCov (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.
estimator_type: MavEstimatorTypeMAVLink field estimator_type.
Class id of the estimator this estimate originated from.
lat: i32MAVLink field lat.
Latitude
lon: i32MAVLink field lon.
Longitude
alt: i32MAVLink field alt.
Altitude in meters above MSL
relative_alt: i32MAVLink field relative_alt.
Altitude above ground
vx: f32MAVLink field vx.
Ground X Speed (Latitude)
vy: f32MAVLink field vy.
Ground Y Speed (Longitude)
vz: f32MAVLink field vz.
Ground Z Speed (Altitude)
covariance: [f32; 36]MAVLink field covariance.
Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
Implementations§
Source§impl GlobalPositionIntCov
impl GlobalPositionIntCov
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 Clone for GlobalPositionIntCov
impl Clone for GlobalPositionIntCov
Source§fn clone(&self) -> GlobalPositionIntCov
fn clone(&self) -> GlobalPositionIntCov
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for GlobalPositionIntCov
impl Debug for GlobalPositionIntCov
Source§impl Default for GlobalPositionIntCov
impl Default for GlobalPositionIntCov
Source§fn default() -> GlobalPositionIntCov
fn default() -> GlobalPositionIntCov
Source§impl<'de> Deserialize<'de> for GlobalPositionIntCov
impl<'de> Deserialize<'de> for GlobalPositionIntCov
Source§fn deserialize<__D>(
__deserializer: __D,
) -> Result<GlobalPositionIntCov, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(
__deserializer: __D,
) -> Result<GlobalPositionIntCov, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
Source§impl From<GlobalPositionIntCov> for Common
impl From<GlobalPositionIntCov> for Common
Source§fn from(value: GlobalPositionIntCov) -> Common
fn from(value: GlobalPositionIntCov) -> Common
Source§impl IntoPayload for GlobalPositionIntCov
impl IntoPayload for GlobalPositionIntCov
Source§impl MessageSpec for GlobalPositionIntCov
impl MessageSpec for GlobalPositionIntCov
Source§impl MessageSpecStatic for GlobalPositionIntCov
impl MessageSpecStatic for GlobalPositionIntCov
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 GlobalPositionIntCov
impl NamedType for GlobalPositionIntCov
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 PartialEq for GlobalPositionIntCov
impl PartialEq for GlobalPositionIntCov
Source§impl Serialize for GlobalPositionIntCov
impl Serialize for GlobalPositionIntCov
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 TryFrom<&Payload> for GlobalPositionIntCov
impl TryFrom<&Payload> for GlobalPositionIntCov
Source§impl Type for GlobalPositionIntCov
impl Type for GlobalPositionIntCov
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.