mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
1b8fc31fcd
commit
dfd7dfc1af
|
@ -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);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue