Enum mavlink::development::MavStandardMode
source · #[repr(u32)]pub enum MavStandardMode {
MAV_STANDARD_MODE_NON_STANDARD = 0,
MAV_STANDARD_MODE_POSITION_HOLD = 1,
MAV_STANDARD_MODE_ORBIT = 2,
MAV_STANDARD_MODE_CRUISE = 3,
MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
MAV_STANDARD_MODE_RETURN_HOME = 5,
MAV_STANDARD_MODE_SAFE_RECOVERY = 6,
MAV_STANDARD_MODE_MISSION = 7,
MAV_STANDARD_MODE_LAND = 8,
MAV_STANDARD_MODE_TAKEOFF = 9,
}
development
only.Expand description
Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a “return” or “RTL” mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. Modes may be set using MAV_CMD_DO_SET_STANDARD_MODE.
Variants§
MAV_STANDARD_MODE_NON_STANDARD = 0
Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode.
MAV_STANDARD_MODE_POSITION_HOLD = 1
Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (“VTOL”) vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process).
MAV_STANDARD_MODE_ORBIT = 2
Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the MAV_CMD_DO_ORBIT for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (“VTOL”) vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process).
MAV_STANDARD_MODE_CRUISE = 3
Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (“VTOL”) vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process).
MAV_STANDARD_MODE_ALTITUDE_HOLD = 4
Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (“VTOL”) vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process).
MAV_STANDARD_MODE_RETURN_HOME = 5
Return home mode (auto). Automatic mode that returns vehicle to home via a safe flight path. It may also automatically land the vehicle (i.e. RTL). The precise flight path and landing behaviour depend on vehicle configuration and type.
MAV_STANDARD_MODE_SAFE_RECOVERY = 6
Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path (rally point or mission defined landing) . It may also automatically land the vehicle. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type.
MAV_STANDARD_MODE_MISSION = 7
Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled.
MAV_STANDARD_MODE_LAND = 8
Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type.
MAV_STANDARD_MODE_TAKEOFF = 9
Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type.
Implementations§
Trait Implementations§
source§impl Clone for MavStandardMode
impl Clone for MavStandardMode
source§fn clone(&self) -> MavStandardMode
fn clone(&self) -> MavStandardMode
1.0.0 · source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moresource§impl Debug for MavStandardMode
impl Debug for MavStandardMode
source§impl Default for MavStandardMode
impl Default for MavStandardMode
source§impl<'de> Deserialize<'de> for MavStandardMode
impl<'de> Deserialize<'de> for MavStandardMode
source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
source§impl FromPrimitive for MavStandardMode
impl FromPrimitive for MavStandardMode
source§fn from_i64(n: i64) -> Option<Self>
fn from_i64(n: i64) -> Option<Self>
i64
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u64(n: u64) -> Option<Self>
fn from_u64(n: u64) -> Option<Self>
u64
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_isize(n: isize) -> Option<Self>
fn from_isize(n: isize) -> Option<Self>
isize
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i8(n: i8) -> Option<Self>
fn from_i8(n: i8) -> Option<Self>
i8
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i16(n: i16) -> Option<Self>
fn from_i16(n: i16) -> Option<Self>
i16
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i32(n: i32) -> Option<Self>
fn from_i32(n: i32) -> Option<Self>
i32
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i128(n: i128) -> Option<Self>
fn from_i128(n: i128) -> Option<Self>
i128
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned. Read moresource§fn from_usize(n: usize) -> Option<Self>
fn from_usize(n: usize) -> Option<Self>
usize
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u8(n: u8) -> Option<Self>
fn from_u8(n: u8) -> Option<Self>
u8
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u16(n: u16) -> Option<Self>
fn from_u16(n: u16) -> Option<Self>
u16
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u32(n: u32) -> Option<Self>
fn from_u32(n: u32) -> Option<Self>
u32
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u128(n: u128) -> Option<Self>
fn from_u128(n: u128) -> Option<Self>
u128
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned. Read moresource§impl PartialEq for MavStandardMode
impl PartialEq for MavStandardMode
source§impl Serialize for MavStandardMode
impl Serialize for MavStandardMode
source§impl ToPrimitive for MavStandardMode
impl ToPrimitive for MavStandardMode
source§fn to_i64(&self) -> Option<i64>
fn to_i64(&self) -> Option<i64>
self
to an i64
. If the value cannot be
represented by an i64
, then None
is returned.source§fn to_u64(&self) -> Option<u64>
fn to_u64(&self) -> Option<u64>
self
to a u64
. If the value cannot be
represented by a u64
, then None
is returned.source§fn to_isize(&self) -> Option<isize>
fn to_isize(&self) -> Option<isize>
self
to an isize
. If the value cannot be
represented by an isize
, then None
is returned.source§fn to_i8(&self) -> Option<i8>
fn to_i8(&self) -> Option<i8>
self
to an i8
. If the value cannot be
represented by an i8
, then None
is returned.source§fn to_i16(&self) -> Option<i16>
fn to_i16(&self) -> Option<i16>
self
to an i16
. If the value cannot be
represented by an i16
, then None
is returned.source§fn to_i32(&self) -> Option<i32>
fn to_i32(&self) -> Option<i32>
self
to an i32
. If the value cannot be
represented by an i32
, then None
is returned.source§fn to_i128(&self) -> Option<i128>
fn to_i128(&self) -> Option<i128>
self
to an i128
. If the value cannot be
represented by an i128
(i64
under the default implementation), then
None
is returned. Read moresource§fn to_usize(&self) -> Option<usize>
fn to_usize(&self) -> Option<usize>
self
to a usize
. If the value cannot be
represented by a usize
, then None
is returned.source§fn to_u8(&self) -> Option<u8>
fn to_u8(&self) -> Option<u8>
self
to a u8
. If the value cannot be
represented by a u8
, then None
is returned.source§fn to_u16(&self) -> Option<u16>
fn to_u16(&self) -> Option<u16>
self
to a u16
. If the value cannot be
represented by a u16
, then None
is returned.source§fn to_u32(&self) -> Option<u32>
fn to_u32(&self) -> Option<u32>
self
to a u32
. If the value cannot be
represented by a u32
, then None
is returned.source§fn to_u128(&self) -> Option<u128>
fn to_u128(&self) -> Option<u128>
self
to a u128
. If the value cannot be
represented by a u128
(u64
under the default implementation), then
None
is returned. Read moreimpl Copy for MavStandardMode
impl StructuralPartialEq for MavStandardMode
Auto Trait Implementations§
impl Freeze for MavStandardMode
impl RefUnwindSafe for MavStandardMode
impl Send for MavStandardMode
impl Sync for MavStandardMode
impl Unpin for MavStandardMode
impl UnwindSafe for MavStandardMode
Blanket Implementations§
source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
source§unsafe fn clone_to_uninit(&self, dst: *mut T)
unsafe fn clone_to_uninit(&self, dst: *mut T)
clone_to_uninit
)