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: u8MAVLink field target_system.
System ID (0 for broadcast).
target_component: u8MAVLink 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: MavOdidStatusMAVLink field status.
Indicates whether the unmanned aircraft is on the ground or in the air.
direction: u16MAVLink 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: u16MAVLink 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: i16MAVLink 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: i32MAVLink field latitude.
Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
longitude: i32MAVLink field longitude.
Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
altitude_barometric: f32MAVLink field altitude_barometric.
The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.
altitude_geodetic: f32MAVLink field altitude_geodetic.
The geodetic altitude as defined by WGS84. If unknown: -1000 m.
height_reference: MavOdidHeightRefMAVLink field height_reference.
Indicates the reference point for the height field.
height: f32MAVLink 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: MavOdidHorAccMAVLink field horizontal_accuracy.
The accuracy of the horizontal position.
vertical_accuracy: MavOdidVerAccMAVLink field vertical_accuracy.
The accuracy of the vertical position.
barometer_accuracy: MavOdidVerAccMAVLink field barometer_accuracy.
The accuracy of the barometric altitude.
speed_accuracy: MavOdidSpeedAccMAVLink field speed_accuracy.
The accuracy of the horizontal and vertical speed.
timestamp: f32MAVLink 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: MavOdidTimeAccMAVLink field timestamp_accuracy.
The accuracy of the timestamps.
Implementations§
Source§impl OpenDroneIdLocation
impl OpenDroneIdLocation
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 OpenDroneIdLocation
impl Clone for OpenDroneIdLocation
Source§fn clone(&self) -> OpenDroneIdLocation
fn clone(&self) -> OpenDroneIdLocation
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for OpenDroneIdLocation
impl Debug for OpenDroneIdLocation
Source§impl Default for OpenDroneIdLocation
impl Default for OpenDroneIdLocation
Source§fn default() -> OpenDroneIdLocation
fn default() -> OpenDroneIdLocation
Source§impl<'de> Deserialize<'de> for OpenDroneIdLocation
impl<'de> Deserialize<'de> for OpenDroneIdLocation
Source§fn deserialize<__D>(
__deserializer: __D,
) -> Result<OpenDroneIdLocation, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(
__deserializer: __D,
) -> Result<OpenDroneIdLocation, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
Source§impl From<OpenDroneIdLocation> for Common
impl From<OpenDroneIdLocation> for Common
Source§fn from(value: OpenDroneIdLocation) -> Common
fn from(value: OpenDroneIdLocation) -> Common
Source§impl IntoPayload for OpenDroneIdLocation
impl IntoPayload for OpenDroneIdLocation
Source§impl MessageSpec for OpenDroneIdLocation
impl MessageSpec for OpenDroneIdLocation
Source§impl MessageSpecStatic for OpenDroneIdLocation
impl MessageSpecStatic for OpenDroneIdLocation
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 OpenDroneIdLocation
impl NamedType for OpenDroneIdLocation
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 OpenDroneIdLocation
impl PartialEq for OpenDroneIdLocation
Source§impl Serialize for OpenDroneIdLocation
impl Serialize for OpenDroneIdLocation
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 OpenDroneIdLocation
impl TryFrom<&Payload> for OpenDroneIdLocation
Source§impl Type for OpenDroneIdLocation
impl Type for OpenDroneIdLocation
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.