pub struct CameraThermalRange {
pub time_boot_ms: u32,
pub stream_id: u8,
pub camera_device_id: u8,
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,
}Expand description
MAVLink CAMERA_THERMAL_RANGE message.
The minimum supported MAVLink version is MAVLink 2.
§Description
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).
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
CameraThermalRange (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).
stream_id: u8MAVLink field stream_id.
Video Stream ID (1 for first, 2 for second, etc.)
camera_device_id: u8MAVLink field camera_device_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).
max: f32MAVLink field max.
Temperature max.
max_point_x: f32MAVLink field max_point_x.
Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.
max_point_y: f32MAVLink field max_point_y.
Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.
min: f32MAVLink field min.
Temperature min.
min_point_x: f32MAVLink field min_point_x.
Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.
min_point_y: f32MAVLink field min_point_y.
Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.
Implementations§
Source§impl CameraThermalRange
impl CameraThermalRange
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> u32
pub const fn message_id() -> u32
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 CameraThermalRange
impl Clone for CameraThermalRange
Source§fn clone(&self) -> CameraThermalRange
fn clone(&self) -> CameraThermalRange
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for CameraThermalRange
impl Debug for CameraThermalRange
Source§impl Default for CameraThermalRange
impl Default for CameraThermalRange
Source§fn default() -> CameraThermalRange
fn default() -> CameraThermalRange
Source§impl<'de> Deserialize<'de> for CameraThermalRange
impl<'de> Deserialize<'de> for CameraThermalRange
Source§fn deserialize<__D>(
__deserializer: __D,
) -> Result<CameraThermalRange, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(
__deserializer: __D,
) -> Result<CameraThermalRange, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
Source§impl From<CameraThermalRange> for Common
impl From<CameraThermalRange> for Common
Source§fn from(value: CameraThermalRange) -> Common
fn from(value: CameraThermalRange) -> Common
Source§impl IntoPayload for CameraThermalRange
impl IntoPayload for CameraThermalRange
Source§impl MessageSpec for CameraThermalRange
impl MessageSpec for CameraThermalRange
Source§impl MessageSpecStatic for CameraThermalRange
impl MessageSpecStatic for CameraThermalRange
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> u32
fn message_id() -> u32
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for CameraThermalRange
impl NamedType for CameraThermalRange
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 CameraThermalRange
impl PartialEq for CameraThermalRange
Source§impl Serialize for CameraThermalRange
impl Serialize for CameraThermalRange
Source§fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
Source§impl TryFrom<&Payload> for CameraThermalRange
impl TryFrom<&Payload> for CameraThermalRange
Source§impl Type for CameraThermalRange
impl Type for CameraThermalRange
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.