Type Alias SetPositionTargetGlobalInt

Source
pub type SetPositionTargetGlobalInt = SetPositionTargetGlobalInt;
Expand description

Aliased Type§

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

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.

§target_system: u8

MAVLink field target_system.

System ID

§target_component: u8

MAVLink field target_component.

Component ID

§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, Relative to home, or AGL - 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