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,
}
Expand description

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§

source§

impl HIL_OPTICAL_FLOW_DATA

source

pub const ENCODED_LEN: usize = 44usize

source

pub const DEFAULT: Self = _

Trait Implementations§

source§

impl Clone for HIL_OPTICAL_FLOW_DATA

source§

fn clone(&self) -> HIL_OPTICAL_FLOW_DATA

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl Debug for HIL_OPTICAL_FLOW_DATA

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl Default for HIL_OPTICAL_FLOW_DATA

source§

fn default() -> Self

Returns the “default value” for a type. Read more
source§

impl<'de> Deserialize<'de> for HIL_OPTICAL_FLOW_DATA

source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
source§

impl MessageData for HIL_OPTICAL_FLOW_DATA

§

type Message = MavMessage

source§

const ID: u32 = 114u32

source§

const NAME: &'static str = "HIL_OPTICAL_FLOW"

source§

const EXTRA_CRC: u8 = 237u8

source§

const ENCODED_LEN: usize = 44usize

source§

fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>

source§

fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize

source§

impl PartialEq for HIL_OPTICAL_FLOW_DATA

source§

fn eq(&self, other: &HIL_OPTICAL_FLOW_DATA) -> bool

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

fn ne(&self, other: &Rhs) -> bool

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl Serialize for HIL_OPTICAL_FLOW_DATA

source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
source§

impl StructuralPartialEq for HIL_OPTICAL_FLOW_DATA

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for Twhere T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T, U> Into<U> for Twhere U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T> ToOwned for Twhere T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
source§

impl<T, U> TryFrom<U> for Twhere U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for Twhere U: TryFrom<T>,

§

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

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<T> DeserializeOwned for Twhere T: for<'de> Deserialize<'de>,