From 13592cef9188a3c61d97d1d941825752fd6f29bb Mon Sep 17 00:00:00 2001 From: yaapu Date: Sun, 10 May 2020 10:29:19 +0200 Subject: [PATCH] AP_Frsky_Telem: removed time constraint to allow SITL regression testing --- libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index 311b2437a3..b95b065f01 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -480,6 +480,7 @@ void AP_Frsky_Telem::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t d buf2[len++] = c; } } +#ifndef HAL_BOARD_SITL /* check that we haven't been too slow in responding to the new UART data. If we respond too late then we will overwrite the next @@ -495,6 +496,7 @@ void AP_Frsky_Telem::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t d // we've been too slow in responding return; } +#endif _port->write(buf2, len); }