From 60a38a0ab12720137b3e176aa585831e6ae17614 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 24 Oct 2023 19:42:14 -0300 Subject: [PATCH] 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 ec2974faaf..2e7d3c61d7 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 d456d91db5..fa271cb08a 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -54,6 +54,8 @@ public: */ 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;