Skip to content

Commit

Permalink
AP_HAL_Linux: set bw_in_bytes_per_second default to 10/100Mbps connec…
Browse files Browse the repository at this point in the history
…tion
  • Loading branch information
Williangalvani authored and tridge committed Oct 31, 2023
1 parent b3f2945 commit 60a38a0
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 0 deletions.
7 changes: 7 additions & 0 deletions libraries/AP_HAL_Linux/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -443,3 +443,10 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
}
return last_receive_us;
}

uint32_t UARTDriver::bw_in_bytes_per_second() const
{
// if connected, assume at least a 10/100Mbps connection
const uint32_t bitrate = (_connected && _ip != nullptr) ? 10E6 : _baudrate;
return bitrate/10; // convert bits to bytes minus overhead
};
2 changes: 2 additions & 0 deletions libraries/AP_HAL_Linux/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class UARTDriver : public AP_HAL::UARTDriver {
*/
uint64_t receive_time_constraint_us(uint16_t nbytes) override;

uint32_t bw_in_bytes_per_second() const override;

private:
AP_HAL::OwnPtr<SerialDevice> _device;
bool _console;
Expand Down

0 comments on commit 60a38a0

Please sign in to comment.