From 55d37e5d0e7039303b943fd8496aaa9e42207828 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 24 Mar 2020 12:39:35 +1100 Subject: [PATCH] GCS_MAVLink: correct slowing down of waypoint re-requests These re-requests shouldn't be slowed down by a factor of 20. This was a left-over from when we did these in terms of 20ms intervals (50Hz loop rate) --- libraries/GCS_MAVLink/MissionItemProtocol.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index 84b711da25..a8633f84f7 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -349,7 +349,7 @@ void MissionItemProtocol::update() return; } // resend request if we haven't gotten one: - const uint32_t wp_recv_timeout_ms = 1000U + (link->get_stream_slowdown_ms()*20); + const uint32_t wp_recv_timeout_ms = 1000U + link->get_stream_slowdown_ms(); if (tnow - timelast_request_ms > wp_recv_timeout_ms) { timelast_request_ms = tnow; link->send_message(next_item_ap_message_id());