mirror of https://github.com/ArduPilot/ardupilot
AP_Networking: fixed discard test on PPP
and fixed byte order bug
This commit is contained in:
parent
8fcc7d5a51
commit
af47beebfc
|
@ -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));
|
||||
}
|
||||
|
||||
|
|
|
@ -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++) {
|
||||
|
|
Loading…
Reference in New Issue