PositionTargetGlobalInt

Struct PositionTargetGlobalInt 

Source
pub struct PositionTargetGlobalInt {
Show 14 fields pub time_boot_ms: u32, pub coordinate_frame: MavFrame, pub type_mask: PositionTargetTypemask, pub lat_int: i32, pub lon_int: i32, pub alt: f32, pub vx: f32, pub vy: f32, pub vz: f32, pub afx: f32, pub afy: f32, pub afz: f32, pub yaw: f32, pub yaw_rate: f32,
}
Expand description

MAVLink POSITION_TARGET_GLOBAL_INT message.

The minimum supported MAVLink version is MAVLink 1.

§Description

Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way.

§Encoding/Decoding

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

Fields§

§time_boot_ms: u32

MAVLink field time_boot_ms.

Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.

§coordinate_frame: MavFrame

MAVLink field coordinate_frame.

Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)

§type_mask: PositionTargetTypemask

MAVLink field type_mask.

Bitmap to indicate which dimensions should be ignored by the vehicle.

§lat_int: i32

MAVLink field lat_int.

Latitude in WGS84 frame

§lon_int: i32

MAVLink field lon_int.

Longitude in WGS84 frame

§alt: f32

MAVLink field alt.

Altitude (MSL, AGL or relative to home altitude, depending on frame)

§vx: f32

MAVLink field vx.

X velocity in NED frame

§vy: f32

MAVLink field vy.

Y velocity in NED frame

§vz: f32

MAVLink field vz.

Z velocity in NED frame

§afx: f32

MAVLink field afx.

X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N

§afy: f32

MAVLink field afy.

Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N

§afz: f32

MAVLink field afz.

Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N

§yaw: f32

MAVLink field yaw.

yaw setpoint

§yaw_rate: f32

MAVLink field yaw_rate.

yaw rate setpoint

Implementations§

Source§

impl PositionTargetGlobalInt

Source

pub const ID: MessageId = 87u32

MavLink message ID.

Source

pub const fn spec() -> MessageInfo

Returns specification for this message.

Source

pub const fn message_id() -> MessageId

Message ID.

Source

pub const fn crc_extra() -> CrcExtra

Message CRC_EXTRA.

Minimum supported MAVLink version for this message.

Trait Implementations§

Source§

impl Clone for PositionTargetGlobalInt

Source§

fn clone(&self) -> PositionTargetGlobalInt

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 PositionTargetGlobalInt

Source§

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

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

impl Default for PositionTargetGlobalInt

Source§

fn default() -> Self

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

impl<'de> Deserialize<'de> for PositionTargetGlobalInt

Source§

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

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

impl From<PositionTargetGlobalInt> for Common

Source§

fn from(value: PositionTargetGlobalInt) -> Self

Converts to this type from the input type.
Source§

impl IntoPayload for PositionTargetGlobalInt

Source§

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

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for PositionTargetGlobalInt

Source§

fn id(&self) -> MessageId

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

fn crc_extra(&self) -> CrcExtra

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

impl MessageSpecStatic for PositionTargetGlobalInt

Source§

fn spec() -> MessageInfo

Returns specification for this message.
Source§

fn message_id() -> MessageId

Message ID.
Source§

fn crc_extra() -> CrcExtra

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

impl NamedType for PositionTargetGlobalInt

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 PositionTargetGlobalInt

Source§

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

Source§

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

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

impl TryFrom<&Payload> for PositionTargetGlobalInt

Source§

type Error = SpecError

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

fn try_from(value: &Payload) -> Result<Self, Self::Error>

Performs the conversion.
Source§

impl Type for PositionTargetGlobalInt

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 PositionTargetGlobalInt

Source§

impl Message for PositionTargetGlobalInt

Source§

impl StructuralPartialEq for PositionTargetGlobalInt

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