CURRENT_MODE_DATA

Struct CURRENT_MODE_DATA 

Source
pub struct CURRENT_MODE_DATA {
    pub custom_mode: u32,
    pub intended_custom_mode: u32,
    pub standard_mode: MavStandardMode,
}
Available on crate feature avssuas only.
Expand description

Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See https://mavlink.io/en/services/standard_modes.html.

ID: 436

Fields§

§custom_mode: u32

A bitfield for use for autopilot-specific flags

§intended_custom_mode: u32

The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied

§standard_mode: MavStandardMode

Standard mode.

Implementations§

Source§

impl CURRENT_MODE_DATA

Source

pub const ENCODED_LEN: usize = 9usize

Source

pub const DEFAULT: Self

Trait Implementations§

Source§

impl Clone for CURRENT_MODE_DATA

Source§

fn clone(&self) -> CURRENT_MODE_DATA

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for CURRENT_MODE_DATA

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for CURRENT_MODE_DATA

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl<'de> Deserialize<'de> for CURRENT_MODE_DATA

Source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Source§

impl MessageData for CURRENT_MODE_DATA

Source§

const ID: u32 = 436u32

Source§

const NAME: &'static str = "CURRENT_MODE"

Source§

const EXTRA_CRC: u8 = 193u8

Source§

const ENCODED_LEN: usize = 9usize

Source§

type Message = MavMessage

Source§

fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>

Source§

fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize

Source§

impl PartialEq for CURRENT_MODE_DATA

Source§

fn eq(&self, other: &CURRENT_MODE_DATA) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl Serialize for CURRENT_MODE_DATA

Source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
Source§

impl StructuralPartialEq for CURRENT_MODE_DATA

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,