pub struct SetPositionTargetGlobalInt {Show 16 fields
pub time_boot_ms: u32,
pub target_system: u8,
pub target_component: u8,
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 SET_POSITION_TARGET_GLOBAL_INT message.
The minimum supported MAVLink version is MAVLink 1.
§Description
Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system).
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
SetPositionTargetGlobalInt (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§time_boot_ms: u32MAVLink 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.
target_system: u8MAVLink field target_system.
System ID
target_component: u8MAVLink field target_component.
Component ID
coordinate_frame: MavFrameMAVLink 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: PositionTargetTypemaskMAVLink field type_mask.
Bitmap to indicate which dimensions should be ignored by the vehicle.
lat_int: i32MAVLink field lat_int.
Latitude in WGS84 frame
lon_int: i32MAVLink field lon_int.
Longitude in WGS84 frame
alt: f32MAVLink field alt.
Altitude (MSL, Relative to home, or AGL - depending on frame)
vx: f32MAVLink field vx.
X velocity in NED frame
vy: f32MAVLink field vy.
Y velocity in NED frame
vz: f32MAVLink field vz.
Z velocity in NED frame
afx: f32MAVLink field afx.
X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afy: f32MAVLink field afy.
Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afz: f32MAVLink field afz.
Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yaw: f32MAVLink field yaw.
yaw setpoint
yaw_rate: f32MAVLink field yaw_rate.
yaw rate setpoint
Implementations§
Source§impl SetPositionTargetGlobalInt
impl SetPositionTargetGlobalInt
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> MessageId
pub const fn message_id() -> MessageId
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 SetPositionTargetGlobalInt
impl Clone for SetPositionTargetGlobalInt
Source§fn clone(&self) -> SetPositionTargetGlobalInt
fn clone(&self) -> SetPositionTargetGlobalInt
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for SetPositionTargetGlobalInt
impl Debug for SetPositionTargetGlobalInt
Source§impl Default for SetPositionTargetGlobalInt
impl Default for SetPositionTargetGlobalInt
Source§impl<'de> Deserialize<'de> for SetPositionTargetGlobalInt
impl<'de> Deserialize<'de> for SetPositionTargetGlobalInt
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Source§impl From<SetPositionTargetGlobalInt> for Common
impl From<SetPositionTargetGlobalInt> for Common
Source§fn from(value: SetPositionTargetGlobalInt) -> Self
fn from(value: SetPositionTargetGlobalInt) -> Self
Source§impl MessageSpecStatic for SetPositionTargetGlobalInt
impl MessageSpecStatic for SetPositionTargetGlobalInt
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> MessageId
fn message_id() -> MessageId
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for SetPositionTargetGlobalInt
impl NamedType for SetPositionTargetGlobalInt
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 TryFrom<&Payload> for SetPositionTargetGlobalInt
impl TryFrom<&Payload> for SetPositionTargetGlobalInt
Source§impl Type for SetPositionTargetGlobalInt
impl Type for SetPositionTargetGlobalInt
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.