From e4bc874083dc0c99ae0157ab1c41ba6cb4b6762c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Dec 2018 17:52:47 +1100 Subject: [PATCH] GCS_MAVLink: cap the minimum message interval to 80% of the main loop rate --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 4f97f7662c..41fb1a6952 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1255,10 +1255,10 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ } } - // send messages out at most once per main loop iteration: + // send messages out at most 80% of main loop rate if (interval_ms != 0 && - interval_ms*1000 < AP::scheduler().get_loop_period_us()) { - interval_ms = AP::scheduler().get_loop_period_us()/1000; + interval_ms*800 < AP::scheduler().get_loop_period_us()) { + interval_ms = AP::scheduler().get_loop_period_us()/800.0; } // check if it's a specially-handled message: