RC_Channel: remove UINT16_MAX check, moved to mavlink handler

This commit is contained in:
Tom Pittenger 2019-05-09 13:52:47 -07:00 committed by Tom Pittenger
parent 4c641c6e2b
commit fc710d8a81

View File

@ -332,12 +332,7 @@ 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().new_override_received();