mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: set bw_in_bytes_per_second to 10/100Mbps connection
This commit is contained in:
parent
b86774789b
commit
b3f2945dcb
|
@ -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
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue