From a15b46b8c9d2b8976dd519ac62733ba7ccb33af2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 25 Jun 2018 15:37:07 +0200 Subject: [PATCH] AirMapTelemetry: rate-limit telemetry to 5Hz --- src/Airmap/AirMapTelemetry.cc | 7 +++++++ src/Airmap/AirMapTelemetry.h | 2 ++ 2 files changed, 9 insertions(+) diff --git a/src/Airmap/AirMapTelemetry.cc b/src/Airmap/AirMapTelemetry.cc index 8550d323b..02b455b1c 100644 --- a/src/Airmap/AirMapTelemetry.cc +++ b/src/Airmap/AirMapTelemetry.cc @@ -67,6 +67,12 @@ AirMapTelemetry::_handleGlobalPositionInt(const mavlink_message_t& message) if (!isTelemetryStreaming()) { return; } + // rate-limit updates to 5 Hz + if (!_timerLastSent.hasExpired(200)) { + return; + } + _timerLastSent.restart(); + mavlink_global_position_int_t globalPosition; mavlink_msg_global_position_int_decode(&message, &globalPosition); Telemetry::Position position{ @@ -123,6 +129,7 @@ AirMapTelemetry::startTelemetryStream(const QString& flightID) QString::fromStdString(result.error().message()), description); } }); + _timerLastSent.start(); } //----------------------------------------------------------------------------- diff --git a/src/Airmap/AirMapTelemetry.h b/src/Airmap/AirMapTelemetry.h index 8b67ae039..707a1dc4a 100644 --- a/src/Airmap/AirMapTelemetry.h +++ b/src/Airmap/AirMapTelemetry.h @@ -15,6 +15,7 @@ #include #include +#include /// Class to send telemetry data to AirMap class AirMapTelemetry : public QObject, public LifetimeChecker @@ -51,5 +52,6 @@ private: std::string _key; ///< key for AES encryption (16 bytes) QString _flightID; float _lastHdop = 1.f; + QElapsedTimer _timerLastSent; }; -- 2.22.0