AP_Networking: allow discard test to be paused

This commit is contained in:
Andrew Tridgell 2023-12-29 07:29:31 +11:00
parent ab24d8768f
commit f0a1a19f8b
1 changed files with 4 additions and 0 deletions

View File

@ -125,6 +125,10 @@ void AP_Networking::test_TCP_discard(void)
uint32_t last_report_ms = AP_HAL::millis(); uint32_t last_report_ms = AP_HAL::millis();
uint32_t total_sent = 0; uint32_t total_sent = 0;
while (true) { while (true) {
if ((param.tests & TEST_TCP_DISCARD) == 0) {
hal.scheduler->delay(1);
continue;
}
total_sent += sock->send(buf, bufsize); total_sent += sock->send(buf, bufsize);
const uint32_t now = AP_HAL::millis(); const uint32_t now = AP_HAL::millis();
if (now - last_report_ms >= 1000) { if (now - last_report_ms >= 1000) {