mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-02-07 10:52:35 +08:00
Use flow rates instead of integrals in backend. This allows us to delay the data to the mitpoint integration time and simplifies the code in general. Gyro compensation can still be done in EKF2 if needed, but the flow module normally already appends the correct gyro data to the flow message.
16 lines
809 B
Plaintext
16 lines
809 B
Plaintext
uint64 timestamp # time since system start (microseconds)
|
|
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
|
|
|
|
float32[2] vel_body # velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s)
|
|
float32[2] vel_ne # same as vel_body but in local frame (m/s)
|
|
|
|
float32[2] flow_rate_uncompensated # integrated optical flow measurement (rad/s)
|
|
float32[2] flow_rate_compensated # integrated optical flow measurement compensated for angular motion (rad/s)
|
|
|
|
float32[3] gyro_rate # gyro measurement synchronized with flow measurements (rad/s)
|
|
|
|
float32[3] gyro_bias
|
|
float32[3] ref_gyro
|
|
|
|
# TOPICS estimator_optical_flow_vel vehicle_optical_flow_vel
|