From 6ac8629451d088d886e82c6e92e6b07e7793acf5 Mon Sep 17 00:00:00 2001 From: Joao Fortuna Date: Thu, 19 Feb 2015 13:50:10 +0100 Subject: [PATCH] Plane: Fixed MAVLINK stream trigger calculation. --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 851efc381c..b7a7b5716c 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -823,7 +823,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; }