[][src]Struct mavlink::common::HIL_OPTICAL_FLOW_DATA

pub struct HIL_OPTICAL_FLOW_DATA {
    pub time_usec: u64,
    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 time_delta_distance_us: u32,
    pub distance: f32,
    pub temperature: i16,
    pub sensor_id: u8,
    pub quality: u8,
}

id: 114 Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor).

Fields

time_usec: u64

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..

integration_time_us: u32

Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the..

integrated_x: f32

Flow in radians 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: f32

Flow in radians 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: f32

RH rotation around X axis.

integrated_ygyro: f32

RH rotation around Y axis.

integrated_zgyro: f32

RH rotation around Z axis.

time_delta_distance_us: u32

Time since the distance was sampled..

distance: f32

Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance..

temperature: i16

Temperature.

sensor_id: u8

Sensor ID.

quality: u8

Optical flow quality / confidence. 0: no valid flow, 255: maximum quality.

Implementations

impl HIL_OPTICAL_FLOW_DATA[src]

pub const ENCODED_LEN: usize[src]

pub fn deser(
    version: MavlinkVersion,
    _input: &[u8]
) -> Result<Self, ParserError>
[src]

pub fn ser(&self) -> Vec<u8>[src]

Trait Implementations

impl Clone for HIL_OPTICAL_FLOW_DATA[src]

impl Debug for HIL_OPTICAL_FLOW_DATA[src]

impl Default for HIL_OPTICAL_FLOW_DATA[src]

impl<'de> Deserialize<'de> for HIL_OPTICAL_FLOW_DATA[src]

impl PartialEq<HIL_OPTICAL_FLOW_DATA> for HIL_OPTICAL_FLOW_DATA[src]

impl Serialize for HIL_OPTICAL_FLOW_DATA[src]

impl StructuralPartialEq for HIL_OPTICAL_FLOW_DATA[src]

Auto Trait Implementations

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> DeserializeOwned for T where
    T: for<'de> Deserialize<'de>, 
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> ToOwned for T where
    T: Clone
[src]

type Owned = T

The resulting type after obtaining ownership.

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.