#[repr(u32)]pub enum MavMode {
MAV_MODE_PREFLIGHT = 0,
MAV_MODE_STABILIZE_DISARMED = 80,
MAV_MODE_STABILIZE_ARMED = 208,
MAV_MODE_MANUAL_DISARMED = 64,
MAV_MODE_MANUAL_ARMED = 192,
MAV_MODE_GUIDED_DISARMED = 88,
MAV_MODE_GUIDED_ARMED = 216,
MAV_MODE_AUTO_DISARMED = 92,
MAV_MODE_AUTO_ARMED = 220,
MAV_MODE_TEST_DISARMED = 66,
MAV_MODE_TEST_ARMED = 194,
}
common
only.Expand description
These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.
Variants§
MAV_MODE_PREFLIGHT = 0
System is not ready to fly, booting, calibrating, etc. No flag is set.
MAV_MODE_STABILIZE_DISARMED = 80
System is allowed to be active, under assisted RC control.
MAV_MODE_STABILIZE_ARMED = 208
System is allowed to be active, under assisted RC control.
MAV_MODE_MANUAL_DISARMED = 64
System is allowed to be active, under manual (RC) control, no stabilization
MAV_MODE_MANUAL_ARMED = 192
System is allowed to be active, under manual (RC) control, no stabilization
MAV_MODE_GUIDED_DISARMED = 88
System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_GUIDED_ARMED = 216
System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_AUTO_DISARMED = 92
System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
MAV_MODE_AUTO_ARMED = 220
System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
MAV_MODE_TEST_DISARMED = 66
UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
MAV_MODE_TEST_ARMED = 194
UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
Implementations§
Trait Implementations§
source§impl<'de> Deserialize<'de> for MavMode
impl<'de> Deserialize<'de> for MavMode
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 MavMode
impl FromPrimitive for MavMode
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 ToPrimitive for MavMode
impl ToPrimitive for MavMode
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 MavMode
impl StructuralPartialEq for MavMode
Auto Trait Implementations§
impl Freeze for MavMode
impl RefUnwindSafe for MavMode
impl Send for MavMode
impl Sync for MavMode
impl Unpin for MavMode
impl UnwindSafe for MavMode
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
)