Plane: do not trust fence-channel PWM during RC failsafe

This commit is contained in:
Peter Barker 2019-11-03 09:08:39 +11:00 committed by Randy Mackay
parent ce963c8f0f
commit bee4ad24d8
1 changed files with 5 additions and 0 deletions

View File

@ -160,6 +160,11 @@ bool Plane::geofence_present(void)
*/
void Plane::geofence_update_pwm_enabled_state()
{
if (rc_failsafe_active()) {
// do nothing based on the radio channel value as it may be at bind value
return;
}
bool is_pwm_enabled;
if (g.fence_channel == 0) {
is_pwm_enabled = false;