Copter: Fixed MAVLINK stream trigger calculation.

This commit is contained in:
João Fortuna 2015-02-19 14:51:26 +01:00 committed by Randy Mackay
parent 73e00108e4
commit b99f38d39d
1 changed files with 1 additions and 1 deletions

View File

@ -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;
}