GlobalPositionIntCov

Struct GlobalPositionIntCov 

Source
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: u64

MAVLink 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: MavEstimatorType

MAVLink field estimator_type.

Class id of the estimator this estimate originated from.

§lat: i32

MAVLink field lat.

Latitude

§lon: i32

MAVLink field lon.

Longitude

§alt: i32

MAVLink field alt.

Altitude in meters above MSL

§relative_alt: i32

MAVLink field relative_alt.

Altitude above ground

§vx: f32

MAVLink field vx.

Ground X Speed (Latitude)

§vy: f32

MAVLink field vy.

Ground Y Speed (Longitude)

§vz: f32

MAVLink 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

Source

pub const ID: u32 = 63u32

MavLink message ID.

Source

pub const fn spec() -> MessageInfo

Returns specification for this message.

Source

pub const fn message_id() -> u32

Message ID.

Source

pub const fn crc_extra() -> u8

Message CRC_EXTRA.

Minimum supported MAVLink version for this message.

Trait Implementations§

Source§

impl Clone for GlobalPositionIntCov

Source§

fn clone(&self) -> GlobalPositionIntCov

Returns a duplicate 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 GlobalPositionIntCov

Source§

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

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

impl Default for GlobalPositionIntCov

Source§

fn default() -> GlobalPositionIntCov

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

impl<'de> Deserialize<'de> for GlobalPositionIntCov

Source§

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

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

impl From<GlobalPositionIntCov> for Common

Source§

fn from(value: GlobalPositionIntCov) -> Common

Converts to this type from the input type.
Source§

impl IntoPayload for GlobalPositionIntCov

Source§

fn encode(&self, version: MavLinkVersion) -> Result<Payload, SpecError>

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for GlobalPositionIntCov

Source§

fn id(&self) -> u32

MAVLink message ID. Read more
Minimum supported MAVLink protocol version. Read more
Source§

fn crc_extra(&self) -> u8

Message EXTRA_CRC calculated from message XML definition. Read more
Source§

impl MessageSpecStatic for GlobalPositionIntCov

Source§

fn spec() -> MessageInfo

Returns specification for this message.
Source§

fn message_id() -> u32

Message ID.
Source§

fn crc_extra() -> u8

Message CRC_EXTRA.
Minimum supported MAVLink version for this message.
Source§

impl NamedType for GlobalPositionIntCov

Source§

fn sid() -> SpectaID

Source§

fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType

this is equivalent to Type::inline but returns a NamedDataType instead.
Source§

fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType

this is equivalent to [Type::definition] but returns a NamedDataType instead.
Source§

impl PartialEq for GlobalPositionIntCov

Source§

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

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

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

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl Serialize for GlobalPositionIntCov

Source§

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

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

impl TryFrom<&Payload> for GlobalPositionIntCov

Source§

type Error = SpecError

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

fn try_from( value: &Payload, ) -> Result<GlobalPositionIntCov, <GlobalPositionIntCov as TryFrom<&Payload>>::Error>

Performs the conversion.
Source§

impl Type for GlobalPositionIntCov

Source§

fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType

Returns the definition of a type using the provided generics. Read more
Source§

fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference

Generates a datatype corresponding to a reference to this type, as determined by its category. Getting a reference to a type implies that it should belong in the type map (since it has to be referenced from somewhere), so the output of definition will be put into the type map.
Source§

impl Flatten for GlobalPositionIntCov

Source§

impl Message for GlobalPositionIntCov

Source§

impl StructuralPartialEq for GlobalPositionIntCov

Auto Trait Implementations§

Blanket Implementations§

Source§

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

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

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

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

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

Source§

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

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. 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 T
where 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> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

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 T
where U: Into<T>,

Source§

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 T
where U: TryFrom<T>,

Source§

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 T
where T: for<'de> Deserialize<'de>,