AP_RCProtocol_UDP: only yield to FDM if enabled

This commit is contained in:
Bob Long 2024-11-27 14:23:50 +11:00
parent fa0754bd90
commit ecdba5681c
1 changed files with 2 additions and 2 deletions

View File

@ -64,8 +64,8 @@ bool AP_RCProtocol_UDP::init()
void AP_RCProtocol_UDP::update()
{
#if AP_RCPROTOCOL_FDM_ENABLED
// yield to the FDM backend if it is getting data
if (fdm_backend->active()) {
// yield to the FDM backend if it is active and getting data
if (protocol_enabled(AP_RCProtocol::FDM) && fdm_backend->active()) {
return;
}
#endif