Struct GpsInput

Source
pub struct GpsInput {
Show 19 fields pub time_usec: u64, pub gps_id: u8, pub ignore_flags: GpsInputIgnoreFlags, pub time_week_ms: u32, pub time_week: u16, pub fix_type: u8, pub lat: i32, pub lon: i32, pub alt: f32, pub hdop: f32, pub vdop: f32, pub vn: f32, pub ve: f32, pub vd: f32, pub speed_accuracy: f32, pub horiz_accuracy: f32, pub vert_accuracy: f32, pub satellites_visible: u8, pub yaw: u16,
}
Expand description

MAVLink GPS_INPUT message.

The minimum supported MAVLink version is MAVLink 1.

§Description

GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system.

§Encoding/Decoding

Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for GpsInput (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.

§gps_id: u8

MAVLink field gps_id.

ID of the GPS for multiple GPS inputs

§ignore_flags: GpsInputIgnoreFlags

MAVLink field ignore_flags.

Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.

§time_week_ms: u32

MAVLink field time_week_ms.

GPS time (from start of GPS week)

§time_week: u16

MAVLink field time_week.

GPS week number

§fix_type: u8

MAVLink field fix_type.

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

§lat: i32

MAVLink field lat.

Latitude (WGS84)

§lon: i32

MAVLink field lon.

Longitude (WGS84)

§alt: f32

MAVLink field alt.

Altitude (MSL). Positive for up.

§hdop: f32

MAVLink field hdop.

GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX

§vdop: f32

MAVLink field vdop.

GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX

§vn: f32

MAVLink field vn.

GPS velocity in north direction in earth-fixed NED frame

§ve: f32

MAVLink field ve.

GPS velocity in east direction in earth-fixed NED frame

§vd: f32

MAVLink field vd.

GPS velocity in down direction in earth-fixed NED frame

§speed_accuracy: f32

MAVLink field speed_accuracy.

GPS speed accuracy

§horiz_accuracy: f32

MAVLink field horiz_accuracy.

GPS horizontal accuracy

§vert_accuracy: f32

MAVLink field vert_accuracy.

GPS vertical accuracy

§satellites_visible: u8

MAVLink field satellites_visible.

Number of satellites visible.

§yaw: u16

MAVLink field yaw.

Yaw of vehicle relative to Earth’s North, zero means not available, use 36000 for north

Implementations§

Source§

impl GpsInput

Source

pub const ID: u32 = 232u32

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 GpsInput

Source§

fn clone(&self) -> GpsInput

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 GpsInput

Source§

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

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

impl Default for GpsInput

Source§

fn default() -> GpsInput

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

impl<'de> Deserialize<'de> for GpsInput

Source§

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

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

impl From<GpsInput> for Common

Source§

fn from(value: GpsInput) -> Common

Converts to this type from the input type.
Source§

impl IntoPayload for GpsInput

Source§

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

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for GpsInput

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 GpsInput

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 GpsInput

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 GpsInput

Source§

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

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 GpsInput

Source§

type Error = SpecError

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

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

Performs the conversion.
Source§

impl Type for GpsInput

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 GpsInput

Source§

impl Message for GpsInput

Source§

impl StructuralPartialEq for GpsInput

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> 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>,