GCS_MAVLink: cap the minimum message interval to 80% of the main loop rate

This commit is contained in:
Peter Barker 2018-12-05 17:52:47 +11:00 committed by Randy Mackay
parent e08a8d03d2
commit e4bc874083

View File

@ -1255,10 +1255,10 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_
}
}
// send messages out at most once per main loop iteration:
// send messages out at most 80% of main loop rate
if (interval_ms != 0 &&
interval_ms*1000 < AP::scheduler().get_loop_period_us()) {
interval_ms = AP::scheduler().get_loop_period_us()/1000;
interval_ms*800 < AP::scheduler().get_loop_period_us()) {
interval_ms = AP::scheduler().get_loop_period_us()/800.0;
}
// check if it's a specially-handled message: