Skip to content

Commit

Permalink
ekf_check: if GPS glitch is active when GPS is regained, set gps glit…
Browse files Browse the repository at this point in the history
…ch mode revert flag

* should prevent vehicle from staying in ALT_HOLD after the following FS sequence:
1. GPS LOST
2. GPS DEGRADED
3. GPS REGAINED
4. GPS RECOVERED
  • Loading branch information
wsilva32 committed Sep 12, 2016
1 parent 6806840 commit 7d2cb35
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 1 deletion.
4 changes: 3 additions & 1 deletion ArduCopter/ekf_check.pde
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,9 @@ static void failsafe_ekf_off_event(void)
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_EKFINAV, ERROR_CODE_FAILSAFE_RESOLVED);

if (ekf_check_switch_mode_on_resolve) {
if (!mode_requires_RC(ekf_check_mode_before_fs_on)) {
if (failsafe.gps_glitch) {
gps_glitch_switch_mode_on_resolve = true;
} else if (!mode_requires_RC(ekf_check_mode_before_fs_on)) {
set_mode_RTL_or_land_with_pause();
} else if (mode_requires_GPS(ekf_check_mode_before_fs_on)) {
set_mode(LOITER);
Expand Down
1 change: 1 addition & 0 deletions Tools/autotest/copter_params.parm
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
FRAME 0
MAG_ENABLE 1
FS_EKF_ACTION 2
FS_THR_ENABLE 1
BATT_MONITOR 4
CH7_OPT 7
Expand Down

0 comments on commit 7d2cb35

Please sign in to comment.