CameraImageCaptured

Struct CameraImageCaptured 

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

MAVLink CAMERA_IMAGE_CAPTURED message.

The minimum supported MAVLink version is MAVLink 2.

§Description

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.

§Encoding/Decoding

Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for CameraImageCaptured (encoding) and [IntoPayload] (decoding) traits. These traits are implemented by Message proc macro.

Fields§

§time_boot_ms: u32

MAVLink field time_boot_ms.

Timestamp (time since system boot).

§time_utc: u64

MAVLink field time_utc.

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

§camera_id: u8

MAVLink field camera_id.

Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id.

§lat: i32

MAVLink field lat.

Latitude where image was taken

§lon: i32

MAVLink field lon.

Longitude where capture was taken

§alt: i32

MAVLink field alt.

Altitude (MSL) where image was taken

§relative_alt: i32

MAVLink field relative_alt.

Altitude above ground

§q: [f32; 4]

MAVLink field q.

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

§image_index: i32

MAVLink field image_index.

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

§capture_result: i8

MAVLink field capture_result.

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

§file_url: [u8; 205]

MAVLink field file_url.

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

Implementations§

Source§

impl CameraImageCaptured

Source

pub const ID: MessageId = 263u32

MavLink message ID.

Source

pub const fn spec() -> MessageInfo

Returns specification for this message.

Source

pub const fn message_id() -> MessageId

Message ID.

Source

pub const fn crc_extra() -> CrcExtra

Message CRC_EXTRA.

Minimum supported MAVLink version for this message.

Trait Implementations§

Source§

impl Clone for CameraImageCaptured

Source§

fn clone(&self) -> CameraImageCaptured

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 CameraImageCaptured

Source§

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

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

impl Default for CameraImageCaptured

Source§

fn default() -> Self

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

impl<'de> Deserialize<'de> for CameraImageCaptured

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 From<CameraImageCaptured> for Common

Source§

fn from(value: CameraImageCaptured) -> Self

Converts to this type from the input type.
Source§

impl IntoPayload for CameraImageCaptured

Source§

fn encode(&self, version: MavLinkVersion) -> Result<Payload, SpecError>

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for CameraImageCaptured

Source§

fn id(&self) -> MessageId

MAVLink message ID. Read more
Minimum supported MAVLink protocol version. Read more
Source§

fn crc_extra(&self) -> CrcExtra

Message EXTRA_CRC calculated from message XML definition. Read more
Source§

impl MessageSpecStatic for CameraImageCaptured

Source§

fn spec() -> MessageInfo

Returns specification for this message.
Source§

fn message_id() -> MessageId

Message ID.
Source§

fn crc_extra() -> CrcExtra

Message CRC_EXTRA.
Minimum supported MAVLink version for this message.
Source§

impl NamedType for CameraImageCaptured

Source§

fn sid() -> SpectaID

Source§

fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType

this is equivalent to Type::inline but returns a NamedDataType instead.
Source§

fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType

this is equivalent to [Type::definition] but returns a NamedDataType instead.
Source§

impl PartialEq for CameraImageCaptured

Source§

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

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 TryFrom<&Payload> for CameraImageCaptured

Source§

type Error = SpecError

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

fn try_from(value: &Payload) -> Result<Self, Self::Error>

Performs the conversion.
Source§

impl Type for CameraImageCaptured

Source§

fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType

Returns the definition of a type using the provided generics. Read more
Source§

fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference

Generates a datatype corresponding to a reference to this type, as determined by its category. Getting a reference to a type implies that it should belong in the type map (since it has to be referenced from somewhere), so the output of definition will be put into the type map.
Source§

impl Flatten for CameraImageCaptured

Source§

impl Message for CameraImageCaptured

Source§

impl StructuralPartialEq for CameraImageCaptured

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> 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>,