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: u32MAVLink field time_boot_ms.
Timestamp (time since system boot).
time_utc: u64MAVLink field time_utc.
Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
camera_id: u8MAVLink 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: i32MAVLink field lat.
Latitude where image was taken
lon: i32MAVLink field lon.
Longitude where capture was taken
alt: i32MAVLink field alt.
Altitude (MSL) where image was taken
relative_alt: i32MAVLink 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: i32MAVLink 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: i8MAVLink 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
impl CameraImageCaptured
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> MessageId
pub const fn message_id() -> MessageId
Message ID.
Sourcepub const fn min_supported_mavlink_version() -> MavLinkVersion
pub const fn min_supported_mavlink_version() -> MavLinkVersion
Minimum supported MAVLink version for this message.
Trait Implementations§
Source§impl Clone for CameraImageCaptured
impl Clone for CameraImageCaptured
Source§fn clone(&self) -> CameraImageCaptured
fn clone(&self) -> CameraImageCaptured
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for CameraImageCaptured
impl Debug for CameraImageCaptured
Source§impl Default for CameraImageCaptured
impl Default for CameraImageCaptured
Source§impl<'de> Deserialize<'de> for CameraImageCaptured
impl<'de> Deserialize<'de> for CameraImageCaptured
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 From<CameraImageCaptured> for Common
impl From<CameraImageCaptured> for Common
Source§fn from(value: CameraImageCaptured) -> Self
fn from(value: CameraImageCaptured) -> Self
Source§impl IntoPayload for CameraImageCaptured
impl IntoPayload for CameraImageCaptured
Source§impl MessageSpec for CameraImageCaptured
impl MessageSpec for CameraImageCaptured
Source§impl MessageSpecStatic for CameraImageCaptured
impl MessageSpecStatic for CameraImageCaptured
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> MessageId
fn message_id() -> MessageId
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for CameraImageCaptured
impl NamedType for CameraImageCaptured
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl PartialEq for CameraImageCaptured
impl PartialEq for CameraImageCaptured
Source§impl Serialize for CameraImageCaptured
impl Serialize for CameraImageCaptured
Source§impl TryFrom<&Payload> for CameraImageCaptured
impl TryFrom<&Payload> for CameraImageCaptured
Source§impl Type for CameraImageCaptured
impl Type for CameraImageCaptured
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.