forked from Archive/PX4-Autopilot
failsafe: set cause to generic when fallback mode is activated
Previously when triggering low battery RTL and then losing GPS, the fallback to Descend would still have low battery as cause.
This commit is contained in:
parent
da39d075ac
commit
70346a5b2f
|
@ -517,6 +517,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::FallbackAltCtrl:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_ALTCTL)) {
|
||||
|
@ -524,6 +526,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::FallbackStab:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_STAB)) {
|
||||
|
@ -531,6 +535,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
} // else: fall through here as well. If stabilized isn't available, we most certainly end up in Terminate
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Hold:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER)) {
|
||||
|
@ -538,6 +544,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::RTL:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL)) {
|
||||
|
@ -545,6 +553,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Land:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND)) {
|
||||
|
@ -552,6 +562,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Descend:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_DESCEND)) {
|
||||
|
@ -559,6 +571,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
|||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Terminate:
|
||||
selected_action = Action::Terminate;
|
||||
|
|
Loading…
Reference in New Issue