Skip to content

Commit

Permalink
AP_HAL_SITL: set bw_in_bytes_per_second to 10/100Mbps connection
Browse files Browse the repository at this point in the history
  • Loading branch information
Williangalvani authored and tridge committed Oct 31, 2023
1 parent b867747 commit b3f2945
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 0 deletions.
6 changes: 6 additions & 0 deletions libraries/AP_HAL_SITL/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

2 changes: 2 additions & 0 deletions libraries/AP_HAL_SITL/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver {
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;

/*
Expand Down

0 comments on commit b3f2945

Please sign in to comment.