OpenDroneIdLocation

Struct OpenDroneIdLocation 

Source
pub struct OpenDroneIdLocation {
Show 19 fields pub target_system: u8, pub target_component: u8, pub id_or_mac: [u8; 20], pub status: MavOdidStatus, pub direction: u16, pub speed_horizontal: u16, pub speed_vertical: i16, pub latitude: i32, pub longitude: i32, pub altitude_barometric: f32, pub altitude_geodetic: f32, pub height_reference: MavOdidHeightRef, pub height: f32, pub horizontal_accuracy: MavOdidHorAcc, pub vertical_accuracy: MavOdidVerAcc, pub barometer_accuracy: MavOdidVerAcc, pub speed_accuracy: MavOdidSpeedAcc, pub timestamp: f32, pub timestamp_accuracy: MavOdidTimeAcc,
}
Expand description

MAVLink OPEN_DRONE_ID_LOCATION message.

The minimum supported MAVLink version is MAVLink 2.

§Description

Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft.

§Encoding/Decoding

Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for OpenDroneIdLocation (encoding) and [IntoPayload] (decoding) traits. These traits are implemented by Message proc macro.

Fields§

§target_system: u8

MAVLink field target_system.

System ID (0 for broadcast).

§target_component: u8

MAVLink field target_component.

Component ID (0 for broadcast).

§id_or_mac: [u8; 20]

MAVLink field id_or_mac.

Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.

§status: MavOdidStatus

MAVLink field status.

Indicates whether the unmanned aircraft is on the ground or in the air.

§direction: u16

MAVLink field direction.

Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.

§speed_horizontal: u16

MAVLink field speed_horizontal.

Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.

§speed_vertical: i16

MAVLink field speed_vertical.

The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.

§latitude: i32

MAVLink field latitude.

Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).

§longitude: i32

MAVLink field longitude.

Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).

§altitude_barometric: f32

MAVLink field altitude_barometric.

The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.

§altitude_geodetic: f32

MAVLink field altitude_geodetic.

The geodetic altitude as defined by WGS84. If unknown: -1000 m.

§height_reference: MavOdidHeightRef

MAVLink field height_reference.

Indicates the reference point for the height field.

§height: f32

MAVLink field height.

The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.

§horizontal_accuracy: MavOdidHorAcc

MAVLink field horizontal_accuracy.

The accuracy of the horizontal position.

§vertical_accuracy: MavOdidVerAcc

MAVLink field vertical_accuracy.

The accuracy of the vertical position.

§barometer_accuracy: MavOdidVerAcc

MAVLink field barometer_accuracy.

The accuracy of the barometric altitude.

§speed_accuracy: MavOdidSpeedAcc

MAVLink field speed_accuracy.

The accuracy of the horizontal and vertical speed.

§timestamp: f32

MAVLink field timestamp.

Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60601000))) / 1000. If unknown: 0xFFFF.

§timestamp_accuracy: MavOdidTimeAcc

MAVLink field timestamp_accuracy.

The accuracy of the timestamps.

Implementations§

Source§

impl OpenDroneIdLocation

Source

pub const ID: u32 = 12_901u32

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 OpenDroneIdLocation

Source§

fn clone(&self) -> OpenDroneIdLocation

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 OpenDroneIdLocation

Source§

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

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

impl Default for OpenDroneIdLocation

Source§

fn default() -> OpenDroneIdLocation

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

impl<'de> Deserialize<'de> for OpenDroneIdLocation

Source§

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

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

impl From<OpenDroneIdLocation> for Common

Source§

fn from(value: OpenDroneIdLocation) -> Common

Converts to this type from the input type.
Source§

impl IntoPayload for OpenDroneIdLocation

Source§

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

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for OpenDroneIdLocation

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 OpenDroneIdLocation

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 OpenDroneIdLocation

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 OpenDroneIdLocation

Source§

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

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 OpenDroneIdLocation

Source§

type Error = SpecError

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

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

Performs the conversion.
Source§

impl Type for OpenDroneIdLocation

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 OpenDroneIdLocation

Source§

impl Message for OpenDroneIdLocation

Source§

impl StructuralPartialEq for OpenDroneIdLocation

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