mirror of https://github.com/ArduPilot/ardupilot
AP_Networking: add timeout to swap the UDP Server client target
This commit is contained in:
parent
d07e8d16df
commit
96682b1b1b
|
@ -270,7 +270,7 @@ private:
|
|||
uint16_t last_udp_connect_port;
|
||||
bool have_received;
|
||||
bool close_on_recv_error;
|
||||
|
||||
uint32_t last_udp_srv_recv_time_ms;
|
||||
HAL_Semaphore sem;
|
||||
};
|
||||
#endif // AP_NETWORKING_REGISTER_PORT_ENABLED
|
||||
|
|
|
@ -350,7 +350,11 @@ bool AP_Networking::Port::send_receive(void)
|
|||
uint32_t last_addr = 0;
|
||||
uint16_t last_port = 0;
|
||||
if (sock->last_recv_address(last_addr, last_port)) {
|
||||
if (!connected || (last_addr != last_udp_connect_address) || (last_port != last_udp_connect_port)) {
|
||||
// we might be disconnected and want to reconnect to a different address/port
|
||||
// if we haven't received anything for a while
|
||||
bool maybe_disconnected = (AP_HAL::millis() - last_udp_srv_recv_time_ms) > 3000 &&
|
||||
((last_addr != last_udp_connect_address) || (last_port != last_udp_connect_port));
|
||||
if (maybe_disconnected || !connected) {
|
||||
char last_addr_str[IP4_STR_LEN];
|
||||
sock->inet_addr_to_str(last_addr, last_addr_str, sizeof(last_addr_str));
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP[%u]: connected to %s:%u", unsigned(state.idx), last_addr_str, unsigned(last_port));
|
||||
|
@ -358,6 +362,10 @@ bool AP_Networking::Port::send_receive(void)
|
|||
last_udp_connect_address = last_addr;
|
||||
last_udp_connect_port = last_port;
|
||||
}
|
||||
// if we received something from the same address, reset the timer
|
||||
if (((last_addr == last_udp_connect_address) && (last_port == last_udp_connect_port))) {
|
||||
last_udp_srv_recv_time_ms = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue