-
Notifications
You must be signed in to change notification settings - Fork 17.5k
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
Add support for Connector loopback testing for Ethernet #28073
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -38,6 +38,11 @@ void AP_Networking::start_tests(void) | |
"TCP_reflect", | ||
8192, AP_HAL::Scheduler::PRIORITY_UART, -1); | ||
} | ||
if (param.tests & TEST_CONNECTOR_LOOPBACK) { | ||
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_connector_loopback, void), | ||
"connector_loopback", | ||
8192, AP_HAL::Scheduler::PRIORITY_UART, -1); | ||
} | ||
} | ||
|
||
/* | ||
|
@@ -200,4 +205,72 @@ void AP_Networking::test_TCP_reflect(void) | |
} | ||
} | ||
|
||
void AP_Networking::test_connector_loopback(void) | ||
{ | ||
startup_wait(); | ||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Connector Loopback: starting"); | ||
|
||
// start tcp discard server | ||
auto *listen_sock = new SocketAPM(false); | ||
if (listen_sock == nullptr) { | ||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to create socket"); | ||
return; | ||
} | ||
listen_sock->reuseaddress(); | ||
|
||
// use netif ip address | ||
char ipstr[16]; | ||
SocketAPM::inet_addr_to_str(get_ip_active(), ipstr, sizeof(ipstr)); | ||
if (!listen_sock->bind(ipstr, 9)) { | ||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to bind"); | ||
return; | ||
} | ||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: bound"); | ||
|
||
if (!listen_sock->listen(1)) { | ||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to listen"); | ||
return; | ||
} | ||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: listening"); | ||
// create discard client | ||
auto *client = new SocketAPM(false); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This is also leaked There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. fixed |
||
if (client == nullptr) { | ||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to create client"); | ||
return; | ||
} | ||
while (!client->connect(ipstr, 9)) { | ||
hal.scheduler->delay(10); | ||
} | ||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: connected"); | ||
|
||
// accept client | ||
auto *sock = listen_sock->accept(100); | ||
if (sock == nullptr) { | ||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to accept"); | ||
return; | ||
} | ||
|
||
uint8_t buf[1024]; | ||
tridge marked this conversation as resolved.
Show resolved
Hide resolved
|
||
uint32_t last_report_ms = AP_HAL::millis(); | ||
uint32_t total_rx = 0; | ||
while (true) { | ||
if ((param.tests & TEST_CONNECTOR_LOOPBACK) == 0) { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. A There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. done |
||
hal.scheduler->delay(1); | ||
continue; | ||
} | ||
client->send(buf, 1024); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I'm pretty sure Valgrind would not like this; maybe just zero it on the stack. I'd actually suggest something non-zero in case there's some ridiculous optimisation somewhere. Perhaps:
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. changed to using memset to set all the values to 0xab |
||
if (sock->pollin(0)) { | ||
const ssize_t ret = sock->recv(buf, sizeof(buf), 0); | ||
if (ret > 0) { | ||
total_rx += ret; | ||
} | ||
} | ||
if (AP_HAL::millis() - last_report_ms >= 1000) { | ||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback throughput %lu kbytes/sec", total_rx/1024); | ||
total_rx = 0; | ||
last_report_ms = AP_HAL::millis(); | ||
} | ||
} | ||
} | ||
|
||
#endif // AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Leaking
listen_sock
here. Similarly elsewhere; use afail:
pattern?There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
fixed