mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: report baudlimit_enable in bw_in_bytes_per_second function
This commit is contained in:
parent
0b95b515bd
commit
d93cc7f113
|
@ -1015,8 +1015,13 @@ ssize_t UARTDriver::get_system_outqueue_length() const
|
||||||
|
|
||||||
uint32_t UARTDriver::bw_in_bytes_per_second() const
|
uint32_t UARTDriver::bw_in_bytes_per_second() const
|
||||||
{
|
{
|
||||||
// if connected, assume at least a 10/100Mbps connection
|
// if connected, assume at least a 10/100Mbps connection if not limited
|
||||||
const uint32_t bitrate = _connected ? 10E6 : _uart_baudrate;
|
bool baud_limit = false;
|
||||||
|
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||||
|
SITL::SIM *_sitl = AP::sitl();
|
||||||
|
baud_limit = (_sitl != nullptr) && _sitl->telem_baudlimit_enable;
|
||||||
|
#endif
|
||||||
|
const uint32_t bitrate = (_connected && !baud_limit) ? 10E6 : _uart_baudrate;
|
||||||
return bitrate/10; // convert bits to bytes minus overhead
|
return bitrate/10; // convert bits to bytes minus overhead
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue