mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
EKF: Use more conservative value for delta velocity bias process noise
Smaller values have resulted in bias estimation divergence under some conditions
This commit is contained in:
parent
21054a4236
commit
a3347b7e06
@ -223,7 +223,7 @@ struct parameters {
|
||||
|
||||
// process noise
|
||||
float gyro_bias_p_noise{1.0e-3f}; ///< process noise for IMU rate gyro bias prediction (rad/sec**2)
|
||||
float accel_bias_p_noise{6.0e-3f}; ///< process noise for IMU accelerometer bias prediction (m/sec**3)
|
||||
float accel_bias_p_noise{1.0e-2f}; ///< process noise for IMU accelerometer bias prediction (m/sec**3)
|
||||
float mage_p_noise{1.0e-3f}; ///< process noise for earth magnetic field prediction (Gauss/sec)
|
||||
float magb_p_noise{1.0e-4f}; ///< process noise for body magnetic field prediction (Gauss/sec)
|
||||
float wind_vel_p_noise{1.0e-1f}; ///< process noise for wind velocity prediction (m/sec**2)
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user