AP_HAL: mark new accept() socket as connected
This commit is contained in:
parent
4cb0a922b2
commit
b49152bbe6
@ -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;
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user