mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Networking: allow reconnection to TCP server or client
This commit is contained in:
parent
5f9abc0406
commit
5a54d9a2ec
@ -13,6 +13,7 @@
|
|||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
#include <AP_HAL/utility/packetise.h>
|
#include <AP_HAL/utility/packetise.h>
|
||||||
|
#include <errno.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -413,6 +414,14 @@ bool AP_Networking::Port::send_receive(void)
|
|||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
writebuffer->advance(ret);
|
writebuffer->advance(ret);
|
||||||
active = true;
|
active = true;
|
||||||
|
} else if (errno == ENOTCONN &&
|
||||||
|
(type == NetworkPortType::TCP_CLIENT || type == NetworkPortType::TCP_SERVER)) {
|
||||||
|
// close socket and mark as disconnected, so we can reconnect with another client or when server comes back
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP[%u]: disconnected", unsigned(state.idx));
|
||||||
|
sock->close();
|
||||||
|
delete sock;
|
||||||
|
sock = nullptr;
|
||||||
|
connected = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user