From b99f38d39dbcb3bb97c6977530945505f7510dbb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Fortuna?= Date: Thu, 19 Feb 2015 14:51:26 +0100 Subject: [PATCH] Copter: Fixed MAVLINK stream trigger calculation. --- ArduCopter/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index af5339a0e9..787b034e01 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -745,7 +745,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num) if (rate > 50) { rate = 50; } - stream_ticks[stream_num] = (50 / rate) + stream_slowdown; + stream_ticks[stream_num] = (50 / rate) - 1 + stream_slowdown; return true; }