pub struct STORAGE_INFORMATION_DATA {
    pub time_boot_ms: u32,
    pub total_capacity: f32,
    pub used_capacity: f32,
    pub available_capacity: f32,
    pub read_speed: f32,
    pub write_speed: f32,
    pub storage_id: u8,
    pub storage_count: u8,
    pub status: StorageStatus,
    pub mavtype: StorageType,
    pub name: [u8; 32],
    pub storage_usage: StorageUsageFlag,
}
Expand description

id: 261 Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc..

Fields§

§time_boot_ms: u32

Timestamp (time since system boot)..

§total_capacity: f32

Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored..

§used_capacity: f32

Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored..

§available_capacity: f32

Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored..

§read_speed: f32

Read speed..

§write_speed: f32

Write speed..

§storage_id: u8

Storage ID (1 for first, 2 for second, etc.).

§storage_count: u8

Number of storage devices.

§status: StorageStatus

Status of storage.

§mavtype: StorageType

Type of storage.

§name: [u8; 32]

Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user..

§storage_usage: StorageUsageFlag

Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types..

Implementations§

source§

impl STORAGE_INFORMATION_DATA

source

pub const ENCODED_LEN: usize = 61usize

source

pub const DEFAULT: Self = _

Trait Implementations§

source§

impl Clone for STORAGE_INFORMATION_DATA

source§

fn clone(&self) -> STORAGE_INFORMATION_DATA

Returns a copy 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 STORAGE_INFORMATION_DATA

source§

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

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

impl Default for STORAGE_INFORMATION_DATA

source§

fn default() -> Self

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

impl<'de> Deserialize<'de> for STORAGE_INFORMATION_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 STORAGE_INFORMATION_DATA

§

type Message = MavMessage

source§

const ID: u32 = 261u32

source§

const NAME: &'static str = "STORAGE_INFORMATION"

source§

const EXTRA_CRC: u8 = 179u8

source§

const ENCODED_LEN: usize = 61usize

source§

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

source§

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

source§

impl PartialEq for STORAGE_INFORMATION_DATA

source§

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

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

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

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl Serialize for STORAGE_INFORMATION_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 STORAGE_INFORMATION_DATA

Auto Trait Implementations§

Blanket Implementations§

source§

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

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

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

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

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

source§

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

Mutably borrows from an owned value. 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 Twhere 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> ToOwned for Twhere T: Clone,

§

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 Twhere U: Into<T>,

§

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 Twhere U: TryFrom<T>,

§

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 Twhere T: for<'de> Deserialize<'de>,