Skip to content

Commit

Permalink
SIM_FlightAxis: adjust socket timeout by framerate
Browse files Browse the repository at this point in the history
This makes socket timeouts faster to detect, causing fewer issues when
they occur.
  • Loading branch information
robertlong13 committed Nov 27, 2024
1 parent af1b960 commit 7f727fe
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_FlightAxis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 7f727fe

Please sign in to comment.