pub struct CAMERA_INFORMATION_DATA {Show 15 fields
pub time_boot_ms: u32,
pub firmware_version: u32,
pub focal_length: f32,
pub sensor_size_h: f32,
pub sensor_size_v: f32,
pub flags: CameraCapFlags,
pub resolution_h: u16,
pub resolution_v: u16,
pub cam_definition_version: u16,
pub vendor_name: [u8; 32],
pub model_name: [u8; 32],
pub lens_id: u8,
pub cam_definition_uri: [u8; 140],
pub gimbal_device_id: u8,
pub camera_device_id: u8,
}
ualberta
only.Expand description
id: 259 Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.
Fields§
§time_boot_ms: u32
Timestamp (time since system boot).
firmware_version: u32
Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
focal_length: f32
Focal length. Use NaN if not known.
sensor_size_h: f32
Image sensor size horizontal. Use NaN if not known.
sensor_size_v: f32
Image sensor size vertical. Use NaN if not known.
flags: CameraCapFlags
Bitmap of camera capability flags.
resolution_h: u16
Horizontal image resolution. Use 0 if not known.
resolution_v: u16
Vertical image resolution. Use 0 if not known.
cam_definition_version: u16
Camera definition version (iteration). Use 0 if not known.
vendor_name: [u8; 32]
Name of the camera vendor
model_name: [u8; 32]
Name of the camera model
lens_id: u8
Reserved for a lens ID. Use 0 if not known.
cam_definition_uri: [u8; 140]
Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
gimbal_device_id: u8
Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.
camera_device_id: u8
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).
Implementations§
Source§impl CAMERA_INFORMATION_DATA
impl CAMERA_INFORMATION_DATA
pub const ENCODED_LEN: usize = 237usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for CAMERA_INFORMATION_DATA
impl Clone for CAMERA_INFORMATION_DATA
Source§fn clone(&self) -> CAMERA_INFORMATION_DATA
fn clone(&self) -> CAMERA_INFORMATION_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more