AP_HAL_Linux: set bw_in_bytes_per_second default to 10/100Mbps connection

This commit is contained in:
Willian Galvani 2023-10-24 19:42:14 -03:00 committed by Andrew Tridgell
parent b3f2945dcb
commit 60a38a0ab1
2 changed files with 9 additions and 0 deletions

View File

@ -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
};

View File

@ -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<SerialDevice> _device;
bool _console;