mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_NavEKF : Reduce GPS position innovation consistency fail threshold
This patch reduces the maximum acceptable GPS jump from approximately 16 to 8 metres This will provide copters with more protection for close in loiter situations
This commit is contained in:
parent
8c0c9c317e
commit
45b1a2fa46
@ -193,7 +193,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
|
|||||||
// @Range: 1 - 100
|
// @Range: 1 - 100
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: advanced
|
// @User: advanced
|
||||||
AP_GROUPINFO("POS_GATE", 18, NavEKF, _gpsPosInnovGate, 10),
|
AP_GROUPINFO("POS_GATE", 18, NavEKF, _gpsPosInnovGate, 5),
|
||||||
|
|
||||||
// @Param: HGT_GATE
|
// @Param: HGT_GATE
|
||||||
// @DisplayName: Height measurement gate size
|
// @DisplayName: Height measurement gate size
|
||||||
|
Loading…
Reference in New Issue
Block a user