SIM_FlightAxis: adjust socket timeout by framerate

This makes socket timeouts faster to detect, causing fewer issues when
they occur.
This commit is contained in:
Bob Long 2024-11-27 14:17:32 +11:00
parent af1b9606e6
commit 7f727feb20
1 changed files with 1 additions and 1 deletions

View File

@ -403,7 +403,7 @@ void FlightAxis::exchange_data(const struct sitl_input &input)
reply = soap_request_end(0);
if (reply == nullptr) {
sock_error_count++;
if (sock_error_count >= 10000 && timestamp_sec() - last_recv_sec > 1) {
if (sock_error_count >= 10000 && timestamp_sec() - last_recv_sec > 3*average_frame_time_s) {
printf("socket timeout\n");
delete sock;
sock = nullptr;