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

Add support for Connector loopback testing for Ethernet #28073

Merged
merged 2 commits into from
Sep 19, 2024

Conversation

bugobliterator
Copy link
Member

Tested working on CubePilot PPPGW

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;
Copy link
Contributor

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 a fail: pattern?

Copy link
Member Author

Choose a reason for hiding this comment

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

fixed

}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: listening");
// create discard client
auto *client = new SocketAPM(false);
Copy link
Contributor

Choose a reason for hiding this comment

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

This is also leaked

Copy link
Member Author

Choose a reason for hiding this comment

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

fixed

uint32_t last_report_ms = AP_HAL::millis();
uint32_t total_rx = 0;
while (true) {
if ((param.tests & TEST_CONNECTOR_LOOPBACK) == 0) {
Copy link
Contributor

Choose a reason for hiding this comment

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

A test_enabled(Test::CONNECTOR_LOOPBACK)` thing would be a nice cleanup

Copy link
Member Author

Choose a reason for hiding this comment

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

done

hal.scheduler->delay(1);
continue;
}
client->send(buf, 1024);
Copy link
Contributor

Choose a reason for hiding this comment

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

for (uint8_t i=0; i<ARRAY_SIZE(buf); i++) {
    buf[i] = i;
}

Copy link
Member Author

Choose a reason for hiding this comment

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

changed to using memset to set all the values to 0xab

@peterbarker peterbarker merged commit 3d47f01 into ArduPilot:master Sep 19, 2024
95 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants