Skip to content

Commit

Permalink
AP_Networking: fixed discard test on PPP
Browse files Browse the repository at this point in the history
and fixed byte order bug
  • Loading branch information
tridge committed Dec 27, 2023
1 parent 0d06772 commit 32d1215
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_Networking/AP_Networking_address.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v)

const char* AP_Networking_IPV4::get_str()
{
const auto ip = ntohl(get_uint32());
const auto ip = get_uint32();
return SocketAPM::inet_addr_to_str(ip, strbuf, sizeof(strbuf));
}

Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Networking/AP_Networking_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,10 +113,10 @@ void AP_Networking::test_TCP_discard(void)
return;
}
// connect to the discard service, which is port 9
if (!sock->connect(dest, 9)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: connect failed");
return;
while (!sock->connect(dest, 9)) {
hal.scheduler->delay(10);
}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: connected");
const uint32_t bufsize = 1024;
uint8_t *buf = (uint8_t*)malloc(bufsize);
for (uint32_t i=0; i<bufsize; i++) {
Expand Down

0 comments on commit 32d1215

Please sign in to comment.