Browse Source

Copter: Fixed MAVLINK stream trigger calculation.

mission-4.1.18
João Fortuna 10 years ago committed by Randy Mackay
parent
commit
b99f38d39d
  1. 2
      ArduCopter/GCS_Mavlink.pde

2
ArduCopter/GCS_Mavlink.pde

@ -745,7 +745,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
if (rate > 50) { if (rate > 50) {
rate = 50; rate = 50;
} }
stream_ticks[stream_num] = (50 / rate) + stream_slowdown; stream_ticks[stream_num] = (50 / rate) - 1 + stream_slowdown;
return true; return true;
} }

Loading…
Cancel
Save