From 965084649761b3cccd92170a12c0b9f399e4ff15 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Aug 2018 16:22:05 +1000 Subject: [PATCH] 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. --- libraries/RC_Channel/RC_Channel.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index b6e418b0a9..4f8432fc10 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -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;