Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_HAL: Improve speed param download in network links (sitl/linux) #25357

Merged
merged 2 commits into from
Oct 31, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
};
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Add a missing newline, otherwise the pre-commit stuff will start to fail again.

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
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