From d93cc7f113582aa9f11cfc5f430153c553abd2d6 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 15 Mar 2024 14:26:49 +0000 Subject: [PATCH] AP_HAL_SITL: report baudlimit_enable in bw_in_bytes_per_second function --- libraries/AP_HAL_SITL/UARTDriver.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 3c58ea02b0..cb645d11f6 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -1015,8 +1015,13 @@ ssize_t UARTDriver::get_system_outqueue_length() const uint32_t UARTDriver::bw_in_bytes_per_second() const { - // if connected, assume at least a 10/100Mbps connection - const uint32_t bitrate = _connected ? 10E6 : _uart_baudrate; + // if connected, assume at least a 10/100Mbps connection if not limited + bool baud_limit = false; +#if !defined(HAL_BUILD_AP_PERIPH) + SITL::SIM *_sitl = AP::sitl(); + baud_limit = (_sitl != nullptr) && _sitl->telem_baudlimit_enable; +#endif + const uint32_t bitrate = (_connected && !baud_limit) ? 10E6 : _uart_baudrate; return bitrate/10; // convert bits to bytes minus overhead };