AP_HAL_SITL: set bw_in_bytes_per_second to 10/100Mbps connection

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

View File

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

View File

@ -46,6 +46,8 @@ public:
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;
/*