AP_HAL: mark new accept() socket as connected

This commit is contained in:
Andrew Tridgell 2023-12-03 16:43:00 +11:00
parent 4cb0a922b2
commit b49152bbe6

View File

@ -391,7 +391,11 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
if (newfd == -1) {
return nullptr;
}
return new SocketAPM(false, newfd);
auto *ret = new SocketAPM(false, newfd);
if (ret) {
ret->connected = true;
}
return ret;
}
/*