forked from Archive/PX4-Autopilot
EKF: increase wind process noise scaler to 0.5
Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
This commit is contained in:
parent
32ca6f7030
commit
7845ff4360
|
@ -238,7 +238,7 @@ struct parameters {
|
|||
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)
|
||||
float wind_vel_p_noise_scaler{0.0f}; ///< scaling of wind process noise with vertical velocity
|
||||
float wind_vel_p_noise_scaler{0.5f}; ///< scaling of wind process noise with vertical velocity
|
||||
float terrain_p_noise{5.0f}; ///< process noise for terrain offset (m/sec)
|
||||
float terrain_gradient{0.5f}; ///< gradient of terrain used to estimate process noise due to changing position (m/m)
|
||||
|
||||
|
|
Loading…
Reference in New Issue