Browse Source

RC_Channel: fix handling of rc_override_time of -1

zr-v5.1
Rob Ratcliff 5 years ago committed by Randy Mackay
parent
commit
5c388507d4
  1. 2
      libraries/RC_Channel/RC_Channel.cpp

2
libraries/RC_Channel/RC_Channel.cpp

@ -359,7 +359,7 @@ bool RC_Channel::has_override() const @@ -359,7 +359,7 @@ bool RC_Channel::has_override() const
}
const float override_timeout_ms = rc().override_timeout_ms();
return is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms);
return (override_timeout_ms < 0) || (is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms));
}
/*

Loading…
Cancel
Save