pub type OpticalFlowRad = OpticalFlowRad;
Expand description
Originally defined in common::messages::optical_flow_rad
.
Aliased Type§
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,
}
Fields§
§time_usec: u64
MAVLink 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: u8
MAVLink field sensor_id
.
Sensor ID
integration_time_us: u32
MAVLink 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: f32
MAVLink 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: f32
MAVLink 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: f32
MAVLink field integrated_xgyro
.
RH rotation around X axis
integrated_ygyro: f32
MAVLink field integrated_ygyro
.
RH rotation around Y axis
integrated_zgyro: f32
MAVLink field integrated_zgyro
.
RH rotation around Z axis
temperature: i16
MAVLink field temperature
.
Temperature
quality: u8
MAVLink field quality
.
Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_us: u32
MAVLink field time_delta_distance_us
.
Time since the distance was sampled.
distance: f32
MAVLink field distance
.
Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.