pub type PositionTargetGlobalInt = PositionTargetGlobalInt;Expand description
Originally defined in common::messages::position_target_global_int.
Aliased Type§
pub struct PositionTargetGlobalInt {}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.
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, AGL or relative to home altitude, 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