mirror of https://github.com/ArduPilot/ardupilot
Copter: Fixed MAVLINK stream trigger calculation.
This commit is contained in:
parent
73e00108e4
commit
b99f38d39d
|
@ -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…
Reference in New Issue