GCS_MAVLink: allow param send in delay callback

this is needed for startup sensor error handling
This commit is contained in:
Andrew Tridgell 2019-01-04 17:56:47 +11:00
parent fe1ac46840
commit 42283b2595

View File

@ -959,7 +959,7 @@ bool GCS_MAVLINK::should_send_message_in_delay_callback(const ap_message id) con
// No ID we return true for may take more than a few hundred
// microseconds to return!
if (id == MSG_HEARTBEAT) {
if (id == MSG_HEARTBEAT || id == MSG_NEXT_PARAM) {
return true;
}