pub type SetPositionTargetLocalNed = SetPositionTargetLocalNed;Expand description
Originally defined in common::messages::set_position_target_local_ned.
Aliased Type§
pub struct SetPositionTargetLocalNed {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 x: f32,
pub y: f32,
pub z: 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: u32MAVLink field time_boot_ms.
Timestamp (time since system boot).
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_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
type_mask: PositionTargetTypemaskMAVLink field type_mask.
Bitmap to indicate which dimensions should be ignored by the vehicle.
x: f32MAVLink field x.
X Position in NED frame
y: f32MAVLink field y.
Y Position in NED frame
z: f32MAVLink field z.
Z Position in NED frame (note, altitude is negative in NED)
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