From dfd7dfc1af4dd74225cf697103b658d355e09fd3 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Thu, 28 Oct 2021 23:18:28 +0530 Subject: [PATCH] Rover: set failsafe_radio flag when RC failsafe is triggered/cleared This sets failsafe_radio flag when RC failsafe is triggered/cleared which is further used in AP_Arming::manual_transmitter_checks to fail pre-arm checks if failsafe is on --- Rover/radio.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Rover/radio.cpp b/Rover/radio.cpp index 5c3ca019fc..cf1f159689 100644 --- a/Rover/radio.cpp +++ b/Rover/radio.cpp @@ -152,5 +152,6 @@ void Rover::radio_failsafe_check(uint16_t pwm) if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 500) { failed = true; } + AP_Notify::flags.failsafe_radio = failed; failsafe_trigger(FAILSAFE_EVENT_THROTTLE, "Radio", failed); }