SITL: use connect_timeout() for realflight

this gives much better handling of network glitches, preventing long
simulation timeouts which impact on the stability of the simulation
This commit is contained in:
Andrew Tridgell 2023-10-20 09:57:09 +11:00
parent 26823b56ae
commit 928d50900a
1 changed files with 5 additions and 1 deletions

View File

@ -595,7 +595,11 @@ void FlightAxis::socket_creator(void)
usleep(500); usleep(500);
continue; continue;
} }
if (!sck->connect(controller_ip, controller_port)) { /*
don't let the connection take more than 100ms (10Hz). Longer
than this and we are better off trying for a new socket
*/
if (!sck->connect_timeout(controller_ip, controller_port, 100)) {
::printf("connect failed\n"); ::printf("connect failed\n");
delete sck; delete sck;
usleep(5000); usleep(5000);