RC_Channel: treat UINT16_MAX as a value of 0 in set_override

This shouldn't really in in RC_Channels - when we move the mavlink
packet handling up to the GCS_MAVLink base class we should move this
into there.
This commit is contained in:
Peter Barker 2018-08-03 16:22:05 +10:00 committed by Peter Barker
parent 1c527df084
commit 9650846497

View File

@ -327,6 +327,12 @@ void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_us)
if (!rc().gcs_overrides_enabled()) {
return;
}
// this UINT16_MAX stuff should really, really be in the
// mavlink packet handling code. It can be moved once that
// code is in the GCS_MAVLink class!
if (v == UINT16_MAX) {
return;
}
last_override_time = timestamp_us != 0 ? timestamp_us : AP_HAL::millis();
override_value = v;
RC_Channels::has_new_overrides = true;