PX4-Autopilot/msg/EstimatorBias.msg
Daniel Agar 8ab65c84ce
ekf2: EV overhaul yaw and position fusion
- new EV position offset estimator
 - yaw_align now strictly means north (no more rotate external vision aid mask)
 - automatically switching between EV yaw, and yaw align north based on
GPS quality
2022-10-28 10:15:17 -04:00

13 lines
661 B
Plaintext

uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32 bias # estimated barometric altitude bias (m)
float32 bias_var # estimated barometric altitude bias variance (m^2)
float32 innov # innovation of the last measurement fusion (m)
float32 innov_var # innovation variance of the last measurement fusion (m^2)
float32 innov_test_ratio # normalized innovation squared test ratio
# TOPICS estimator_baro_bias estimator_gnss_hgt_bias estimator_rng_hgt_bias