From 8a84dbc19e82da766a9eb4d048cb0c1da860986e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 25 Mar 2020 15:09:57 +1100 Subject: [PATCH] GCS_MAVLink: slow down telemetry during ftp --- libraries/GCS_MAVLink/GCS.h | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 6 ++++++ libraries/GCS_MAVLink/GCS_FTP.cpp | 1 + 3 files changed, 8 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 49eb6d006a..0322446e98 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -707,6 +707,7 @@ private: int fd = -1; FTP_FILE_MODE mode; // work around AP_Filesystem not supporting file modes int16_t current_session; + uint32_t last_send_ms; }; static struct ftp_state ftp; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 48c19a01ac..28eb2945f9 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -847,6 +847,12 @@ uint16_t GCS_MAVLINK::get_reschedule_interval_ms(const deferred_message_bucket_t // we are sending requests for waypoints, penalize streams: interval_ms *= 4; } +#if HAVE_FILESYSTEM_SUPPORT + if (ftp.replies && AP_HAL::millis() - ftp.last_send_ms < 500) { + // we are sending ftp replies + interval_ms *= 4; + } +#endif if (interval_ms > 60000) { return 60000; diff --git a/libraries/GCS_MAVLink/GCS_FTP.cpp b/libraries/GCS_MAVLink/GCS_FTP.cpp index ae015dfa93..121e773c95 100644 --- a/libraries/GCS_MAVLink/GCS_FTP.cpp +++ b/libraries/GCS_MAVLink/GCS_FTP.cpp @@ -114,6 +114,7 @@ void GCS_MAVLINK::send_ftp_replies(void) { 0, reply.sysid, reply.compid, payload); ftp.replies->pop(reply); + ftp.last_send_ms = AP_HAL::millis(); } else { return; }