From b1b0d698baea3fc4c77a7244a3cae1fd3d2981d9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 24 May 2022 11:11:08 +1200 Subject: [PATCH] core: fix another double promise The problem is that the function called when a timeout happens, always calls the _all_params_callback which it should not. In fact, there should be two different timeout handlers instead. --- src/mavsdk/core/mavlink_parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mavsdk/core/mavlink_parameters.cpp b/src/mavsdk/core/mavlink_parameters.cpp index 145371b83d..95f1534836 100644 --- a/src/mavsdk/core/mavlink_parameters.cpp +++ b/src/mavsdk/core/mavlink_parameters.cpp @@ -913,6 +913,7 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t& message) if (param_value.param_index + 1 == param_value.param_count) { _parent.unregister_timeout_handler(_all_params_timeout_cookie); _all_params_callback(_all_params); + _all_params_callback = nullptr; } else { _parent.unregister_timeout_handler(_all_params_timeout_cookie);