mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: Fixed MAVLINK stream trigger calculation.
This commit is contained in:
parent
b99f38d39d
commit
6ac8629451
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user