Copter: EKF failsafe action always Land if RC failsafe active
This commit is contained in:
parent
6d266d2063
commit
598925f8d2
@ -141,7 +141,7 @@ void Copter::failsafe_ekf_event()
|
|||||||
switch (g.fs_ekf_action) {
|
switch (g.fs_ekf_action) {
|
||||||
case FS_EKF_ACTION_ALTHOLD:
|
case FS_EKF_ACTION_ALTHOLD:
|
||||||
// AltHold
|
// AltHold
|
||||||
if (!set_mode(ALT_HOLD)) {
|
if (failsafe.radio || !set_mode(ALT_HOLD)) {
|
||||||
set_mode_land_with_pause();
|
set_mode_land_with_pause();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user