Struct mavlink::ardupilotmega::CAMERA_STATUS_DATA
source · pub struct CAMERA_STATUS_DATA {
pub time_usec: u64,
pub p1: f32,
pub p2: f32,
pub p3: f32,
pub p4: f32,
pub img_idx: u16,
pub target_system: u8,
pub cam_idx: u8,
pub event_id: CameraStatusTypes,
}
Available on crate feature
ardupilotmega
only.Expand description
id: 179 Camera Event..
Fields§
§time_usec: u64
Image timestamp (since UNIX epoch, according to camera clock)..
p1: f32
Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum)..
p2: f32
Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum)..
p3: f32
Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum)..
p4: f32
Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum)..
img_idx: u16
Image index..
target_system: u8
System ID..
cam_idx: u8
Camera ID..
event_id: CameraStatusTypes
Event type..
Implementations§
source§impl CAMERA_STATUS_DATA
impl CAMERA_STATUS_DATA
pub const ENCODED_LEN: usize = 29usize
pub const DEFAULT: Self = _
Trait Implementations§
source§impl Clone for CAMERA_STATUS_DATA
impl Clone for CAMERA_STATUS_DATA
source§fn clone(&self) -> CAMERA_STATUS_DATA
fn clone(&self) -> CAMERA_STATUS_DATA
Returns a copy of the value. Read more
1.0.0 · source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from
source
. Read moresource§impl Debug for CAMERA_STATUS_DATA
impl Debug for CAMERA_STATUS_DATA
source§impl Default for CAMERA_STATUS_DATA
impl Default for CAMERA_STATUS_DATA
source§impl<'de> Deserialize<'de> for CAMERA_STATUS_DATA
impl<'de> Deserialize<'de> for CAMERA_STATUS_DATA
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>,
Deserialize this value from the given Serde deserializer. Read more
source§impl MessageData for CAMERA_STATUS_DATA
impl MessageData for CAMERA_STATUS_DATA
const ID: u32 = 179u32
const NAME: &'static str = "CAMERA_STATUS"
const EXTRA_CRC: u8 = 189u8
const ENCODED_LEN: usize = 29usize
type Message = MavMessage
fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize
source§impl PartialEq for CAMERA_STATUS_DATA
impl PartialEq for CAMERA_STATUS_DATA
source§impl Serialize for CAMERA_STATUS_DATA
impl Serialize for CAMERA_STATUS_DATA
impl StructuralPartialEq for CAMERA_STATUS_DATA
Auto Trait Implementations§
impl Freeze for CAMERA_STATUS_DATA
impl RefUnwindSafe for CAMERA_STATUS_DATA
impl Send for CAMERA_STATUS_DATA
impl Sync for CAMERA_STATUS_DATA
impl Unpin for CAMERA_STATUS_DATA
impl UnwindSafe for CAMERA_STATUS_DATA
Blanket Implementations§
source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
source§unsafe fn clone_to_uninit(&self, dst: *mut T)
unsafe fn clone_to_uninit(&self, dst: *mut T)
🔬This is a nightly-only experimental API. (
clone_to_uninit
)