pub struct OpticalFlowRad {
pub time_usec: u64,
pub sensor_id: u8,
pub integration_time_us: u32,
pub integrated_x: f32,
pub integrated_y: f32,
pub integrated_xgyro: f32,
pub integrated_ygyro: f32,
pub integrated_zgyro: f32,
pub temperature: i16,
pub quality: u8,
pub time_delta_distance_us: u32,
pub distance: f32,
}Expand description
MAVLink OPTICAL_FLOW_RAD message.
The minimum supported MAVLink version is MAVLink 1.
§Description
Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
OpticalFlowRad (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§time_usec: u64MAVLink field time_usec.
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
sensor_id: u8MAVLink field sensor_id.
Sensor ID
integration_time_us: u32MAVLink field integration_time_us.
Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
integrated_x: f32MAVLink field integrated_x.
Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
integrated_y: f32MAVLink field integrated_y.
Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
integrated_xgyro: f32MAVLink field integrated_xgyro.
RH rotation around X axis
integrated_ygyro: f32MAVLink field integrated_ygyro.
RH rotation around Y axis
integrated_zgyro: f32MAVLink field integrated_zgyro.
RH rotation around Z axis
temperature: i16MAVLink field temperature.
Temperature
quality: u8MAVLink field quality.
Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_us: u32MAVLink field time_delta_distance_us.
Time since the distance was sampled.
distance: f32MAVLink field distance.
Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
Implementations§
Source§impl OpticalFlowRad
impl OpticalFlowRad
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 OpticalFlowRad
impl Clone for OpticalFlowRad
Source§fn clone(&self) -> OpticalFlowRad
fn clone(&self) -> OpticalFlowRad
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for OpticalFlowRad
impl Debug for OpticalFlowRad
Source§impl Default for OpticalFlowRad
impl Default for OpticalFlowRad
Source§impl<'de> Deserialize<'de> for OpticalFlowRad
impl<'de> Deserialize<'de> for OpticalFlowRad
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<OpticalFlowRad> for Common
impl From<OpticalFlowRad> for Common
Source§fn from(value: OpticalFlowRad) -> Self
fn from(value: OpticalFlowRad) -> Self
Source§impl IntoPayload for OpticalFlowRad
impl IntoPayload for OpticalFlowRad
Source§impl MessageSpec for OpticalFlowRad
impl MessageSpec for OpticalFlowRad
Source§impl MessageSpecStatic for OpticalFlowRad
impl MessageSpecStatic for OpticalFlowRad
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 OpticalFlowRad
impl NamedType for OpticalFlowRad
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 OpticalFlowRad
impl PartialEq for OpticalFlowRad
Source§impl Serialize for OpticalFlowRad
impl Serialize for OpticalFlowRad
Source§impl TryFrom<&Payload> for OpticalFlowRad
impl TryFrom<&Payload> for OpticalFlowRad
Source§impl Type for OpticalFlowRad
impl Type for OpticalFlowRad
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.