pub struct CAMERA_THERMAL_RANGE_DATA {
pub time_boot_ms: u32,
pub max: f32,
pub max_point_x: f32,
pub max_point_y: f32,
pub min: f32,
pub min_point_x: f32,
pub min_point_y: f32,
pub stream_id: u8,
pub camera_device_id: u8,
}
storm32
only.Expand description
id: 277
Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS flag
field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras).
Fields§
§time_boot_ms: u32
Timestamp (time since system boot).
max: f32
Temperature max.
max_point_x: f32
Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.
max_point_y: f32
Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.
min: f32
Temperature min.
min_point_x: f32
Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.
min_point_y: f32
Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.
stream_id: u8
Video Stream ID (1 for first, 2 for second, etc.)
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_THERMAL_RANGE_DATA
impl CAMERA_THERMAL_RANGE_DATA
pub const ENCODED_LEN: usize = 30usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for CAMERA_THERMAL_RANGE_DATA
impl Clone for CAMERA_THERMAL_RANGE_DATA
Source§fn clone(&self) -> CAMERA_THERMAL_RANGE_DATA
fn clone(&self) -> CAMERA_THERMAL_RANGE_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more