From 31aea781c73305630ab7b4ae2fa393f1b585842c Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 24 Oct 2023 19:32:42 -0300 Subject: [PATCH 1/2] AP_HAL_SITL: set bw_in_bytes_per_second to 10/100Mbps connection --- libraries/AP_HAL_SITL/UARTDriver.cpp | 6 ++++++ libraries/AP_HAL_SITL/UARTDriver.h | 2 ++ 2 files changed, 8 insertions(+) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 7b43217e67f1e..9c90928630dea 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -987,5 +987,11 @@ ssize_t UARTDriver::get_system_outqueue_length() const #endif } +uint32_t UARTDriver::bw_in_bytes_per_second() const +{ + // if connected, assume at least a 10/100Mbps connection + const uint32_t bitrate = (_connected && _tcp_client_addr != nullptr) ? 10E6 : _uart_baudrate; + return bitrate/10; // convert bits to bytes minus overhead +}; #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index fb0476550bb21..d47378a8054da 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -46,6 +46,8 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { void set_stop_bits(int n) override; bool set_unbuffered_writes(bool on) override; + uint32_t bw_in_bytes_per_second() const override; + void _timer_tick(void) override; /* From 4bdd3ae9a5abdbd275e4f304f77f74024f4bbe9d Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 24 Oct 2023 19:42:14 -0300 Subject: [PATCH 2/2] AP_HAL_Linux: set bw_in_bytes_per_second default to 10/100Mbps connection --- libraries/AP_HAL_Linux/UARTDriver.cpp | 7 +++++++ libraries/AP_HAL_Linux/UARTDriver.h | 2 ++ 2 files changed, 9 insertions(+) diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index ec2974faaf548..2e7d3c61d7d70 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -443,3 +443,10 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) } return last_receive_us; } + +uint32_t UARTDriver::bw_in_bytes_per_second() const +{ + // if connected, assume at least a 10/100Mbps connection + const uint32_t bitrate = (_connected && _ip != nullptr) ? 10E6 : _baudrate; + return bitrate/10; // convert bits to bytes minus overhead +}; \ No newline at end of file diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index d456d91db51ea..fa271cb08add0 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -54,6 +54,8 @@ class UARTDriver : public AP_HAL::UARTDriver { */ uint64_t receive_time_constraint_us(uint16_t nbytes) override; + uint32_t bw_in_bytes_per_second() const override; + private: AP_HAL::OwnPtr _device; bool _console;