From ca7fcc093c28acdda92cb0a6ca4f3ade9c93edb5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 24 Mar 2020 12:36:25 +1100 Subject: [PATCH] GCS_MAVLink: correct return type on get_stream_slowdown_ms Only used in one place. On slow links may have caused us to re-request a waypoint too often. "Too often" is still >1s intervals. --- libraries/GCS_MAVLink/GCS.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 835eb40a72..9099a7c91e 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -292,7 +292,7 @@ public: static const struct stream_entries all_stream_entries[]; virtual uint64_t capabilities() const; - uint8_t get_stream_slowdown_ms() const { return stream_slowdown_ms; } + uint16_t get_stream_slowdown_ms() const { return stream_slowdown_ms; } MAV_RESULT set_message_interval(uint32_t msg_id, int32_t interval_us);