pub struct CAMERA_IMAGE_CAPTURED_DATA {
    pub time_utc: u64,
    pub time_boot_ms: u32,
    pub lat: i32,
    pub lon: i32,
    pub alt: i32,
    pub relative_alt: i32,
    pub q: [f32; 4],
    pub image_index: i32,
    pub camera_id: u8,
    pub capture_result: i8,
    pub file_url: [u8; 205],
}
Expand description

id: 263 Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range..

Fields§

§time_utc: u64

Timestamp (time since UNIX epoch) in UTC. 0 for unknown..

§time_boot_ms: u32

Timestamp (time since system boot)..

§lat: i32

Latitude where image was taken.

§lon: i32

Longitude where capture was taken.

§alt: i32

Altitude (MSL) where image was taken.

§relative_alt: i32

Altitude above ground.

§q: [f32; 4]

Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0).

§image_index: i32

Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1).

§camera_id: u8

Deprecated/unused. Component IDs are used to differentiate multiple cameras..

§capture_result: i8

Boolean indicating success (1) or failure (0) while capturing this image..

§file_url: [u8; 205]

URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface..

Implementations§

source§

impl CAMERA_IMAGE_CAPTURED_DATA

source

pub const ENCODED_LEN: usize = 255usize

source

pub const DEFAULT: Self = _

Trait Implementations§

source§

impl Clone for CAMERA_IMAGE_CAPTURED_DATA

source§

fn clone(&self) -> CAMERA_IMAGE_CAPTURED_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 CAMERA_IMAGE_CAPTURED_DATA

source§

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

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

impl Default for CAMERA_IMAGE_CAPTURED_DATA

source§

fn default() -> Self

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

impl<'de> Deserialize<'de> for CAMERA_IMAGE_CAPTURED_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 CAMERA_IMAGE_CAPTURED_DATA

§

type Message = MavMessage

source§

const ID: u32 = 263u32

source§

const NAME: &'static str = "CAMERA_IMAGE_CAPTURED"

source§

const EXTRA_CRC: u8 = 133u8

source§

const ENCODED_LEN: usize = 255usize

source§

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

source§

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

source§

impl PartialEq for CAMERA_IMAGE_CAPTURED_DATA

source§

fn eq(&self, other: &CAMERA_IMAGE_CAPTURED_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 CAMERA_IMAGE_CAPTURED_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 CAMERA_IMAGE_CAPTURED_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>,