AP_HAL: mark socket as not connected on EOF

this allows lua scripts to properly detect a closed TCP connection
This commit is contained in:
Andrew Tridgell 2023-12-05 13:51:03 +11:00
parent 64d649fbcc
commit a77331e725

View File

@ -295,6 +295,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
ssize_t ret;
ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len);
if (ret <= 0) {
if (!datagram && connected && ret == 0) {
// remote host has closed connection
connected = false;
}
return ret;
}
if (fd_in != -1) {