From 3338de827e67ba658f919a94ebcea2c5ba9c4116 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2017 18:11:41 +1000 Subject: [PATCH] GCS_MAVLink: remove unneeded telemetry_delayed parameter Also make it protected --- libraries/GCS_MAVLink/GCS.h | 7 +++---- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 5fbc9ecc7d..e0f1d32a31 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -212,10 +212,6 @@ public: // return current packet overhead for a channel static uint8_t packet_overhead_chan(mavlink_channel_t chan); - // FIXME: move this to be private/protected once possible - bool telemetry_delayed(mavlink_channel_t chan); - virtual uint32_t telem_delay() const = 0; - protected: // overridable method to check for packet acceptance. Allows for @@ -269,6 +265,9 @@ protected: void handle_timesync(mavlink_message_t *msg); void handle_statustext(mavlink_message_t *msg); + bool telemetry_delayed() const; + virtual uint32_t telem_delay() const = 0; + private: float adjust_rate_for_stream_trigger(enum streams stream_num); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 34b99bf89d..578f490c4b 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1520,13 +1520,13 @@ float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num) } // are we still delaying telemetry to try to avoid Xbee bricking? -bool GCS_MAVLINK::telemetry_delayed(mavlink_channel_t _chan) +bool GCS_MAVLINK::telemetry_delayed() const { uint32_t tnow = AP_HAL::millis() >> 10; if (tnow > telem_delay()) { return false; } - if (_chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) { + if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) { // this is USB telemetry, so won't be an Xbee return false; }