Skip to content

Commit

Permalink
AP_HAL_SITL: report baudlimit_enable in bw_in_bytes_per_second function
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Apr 3, 2024
1 parent 0b95b51 commit d93cc7f
Showing 1 changed file with 7 additions and 2 deletions.
9 changes: 7 additions & 2 deletions libraries/AP_HAL_SITL/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1015,8 +1015,13 @@ ssize_t UARTDriver::get_system_outqueue_length() const

uint32_t UARTDriver::bw_in_bytes_per_second() const
{
// if connected, assume at least a 10/100Mbps connection
const uint32_t bitrate = _connected ? 10E6 : _uart_baudrate;
// if connected, assume at least a 10/100Mbps connection if not limited
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
};

Expand Down

0 comments on commit d93cc7f

Please sign in to comment.