mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_NavEKF : Update default tuning parameters (for plane use)
This commit is contained in:
parent
d0828d9c15
commit
dacba5d911
@ -31,7 +31,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
|
|||||||
// @Range: 0.05 - 5.0
|
// @Range: 0.05 - 5.0
|
||||||
// @Increment: 0.05
|
// @Increment: 0.05
|
||||||
// @User: advanced
|
// @User: advanced
|
||||||
AP_GROUPINFO("VELNE_NOISE", 0, NavEKF, _gpsHorizVelNoise, 0.15f),
|
AP_GROUPINFO("VELNE_NOISE", 0, NavEKF, _gpsHorizVelNoise, 0.30f),
|
||||||
|
|
||||||
// @Param: VELD_NOISE
|
// @Param: VELD_NOISE
|
||||||
// @DisplayName: GPS vertical velocity measurement noise (m/s)
|
// @DisplayName: GPS vertical velocity measurement noise (m/s)
|
||||||
@ -103,7 +103,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
|
|||||||
// @Range: 0.05 - 1.0 AP_Float _gpsNEVelVarAccScale; // scale factor applied to NE velocity measurement variance due to Vdot
|
// @Range: 0.05 - 1.0 AP_Float _gpsNEVelVarAccScale; // scale factor applied to NE velocity measurement variance due to Vdot
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @User: advanced
|
// @User: advanced
|
||||||
AP_GROUPINFO("ACC_PNOISE", 9, NavEKF, _accNoise, 0.50f),
|
AP_GROUPINFO("ACC_PNOISE", 9, NavEKF, _accNoise, 0.25f),
|
||||||
|
|
||||||
// @Param: GBIAS_PNOISE
|
// @Param: GBIAS_PNOISE
|
||||||
// @DisplayName: Rate gyro bias state process noise (rad/s)
|
// @DisplayName: Rate gyro bias state process noise (rad/s)
|
||||||
|
Loading…
Reference in New Issue
Block a user