Browse Source

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
gps-1.3.1
Shiv Tyagi 3 years ago committed by Randy Mackay
parent
commit
dfd7dfc1af
  1. 1
      Rover/radio.cpp

1
Rover/radio.cpp

@ -152,5 +152,6 @@ void Rover::radio_failsafe_check(uint16_t pwm) @@ -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…
Cancel
Save