pub struct MISSION_SET_CURRENT_DATA {
pub seq: u16,
pub target_system: u8,
pub target_component: u8,
}
asluav
only.Expand description
id: 41 Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode..
Fields§
§seq: u16
Sequence.
target_system: u8
System ID.
target_component: u8
Component ID.
Implementations§
Source§impl MISSION_SET_CURRENT_DATA
impl MISSION_SET_CURRENT_DATA
pub const ENCODED_LEN: usize = 4usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for MISSION_SET_CURRENT_DATA
impl Clone for MISSION_SET_CURRENT_DATA
Source§fn clone(&self) -> MISSION_SET_CURRENT_DATA
fn clone(&self) -> MISSION_SET_CURRENT_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more