mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_Common: whitelist AUTOPILOT_VERSION for in_delay_callback sending
GCSs may request this very early on in the boot process, particularly for SITL. If we try to send it during a delay callback then we end up dropping it at the moment - but we'd already sent the ack in response to the request.
This commit is contained in:
parent
ca4af94833
commit
5100c9fb8c
@ -791,10 +791,6 @@ 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 || id == MSG_NEXT_PARAM) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (in_hil_mode()) {
|
||||
// in HIL we need to keep sending servo values to ensure
|
||||
// the simulator doesn't pause, otherwise our sensor
|
||||
@ -805,6 +801,15 @@ bool GCS_MAVLINK::should_send_message_in_delay_callback(const ap_message id) con
|
||||
}
|
||||
}
|
||||
|
||||
switch (id) {
|
||||
case MSG_HEARTBEAT:
|
||||
case MSG_NEXT_PARAM:
|
||||
case MSG_AUTOPILOT_VERSION:
|
||||
return true;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user