pub struct MISSION_ITEM_INT_DATA {}
asluav
only.Expand description
id: 73 Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component’s current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html..
Fields§
§param1: f32
PARAM1, see MAV_CMD enum.
param2: f32
PARAM2, see MAV_CMD enum.
param3: f32
PARAM3, see MAV_CMD enum.
param4: f32
PARAM4, see MAV_CMD enum.
x: i32
PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7.
y: i32
PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7.
z: f32
PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame..
seq: u16
Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)..
command: MavCmd
The scheduled action for the waypoint..
target_system: u8
System ID.
target_component: u8
Component ID.
frame: MavFrame
The coordinate system of the waypoint..
current: u8
false:0, true:1.
autocontinue: u8
Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes..
mission_type: MavMissionType
Mission type..
Implementations§
Source§impl MISSION_ITEM_INT_DATA
impl MISSION_ITEM_INT_DATA
pub const ENCODED_LEN: usize = 38usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for MISSION_ITEM_INT_DATA
impl Clone for MISSION_ITEM_INT_DATA
Source§fn clone(&self) -> MISSION_ITEM_INT_DATA
fn clone(&self) -> MISSION_ITEM_INT_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more