From 5fde927dc9bad8572995f8586bcad9ce25531537 Mon Sep 17 00:00:00 2001 From: Pavlo Kolomiiets Date: Wed, 11 Sep 2024 09:25:25 +0300 Subject: [PATCH] core: Fix reading int8/16 params from ArduPilot When reading one-by-one with get_param_int --- src/mavsdk/core/mavlink_parameter_client.cpp | 23 ++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/src/mavsdk/core/mavlink_parameter_client.cpp b/src/mavsdk/core/mavlink_parameter_client.cpp index 57d72e956..cd5a918b3 100644 --- a/src/mavsdk/core/mavlink_parameter_client.cpp +++ b/src/mavsdk/core/mavlink_parameter_client.cpp @@ -293,6 +293,29 @@ void MavlinkParameterClient::get_param_async_typesafe( get_param_async(name, callback_future_result, cookie); } +template<> +void MavlinkParameterClient::get_param_async_typesafe( + const std::string& name, const GetParamTypesafeCallback callback, const void* cookie) +{ + // We need to delay the type checking until we get a response from the server. + GetParamAnyCallback callback_future_result = [callback](Result result, ParamValue value) { + if (result == Result::Success) { + if (value.is()) { + callback(Result::Success, value.get()); + } else if (value.is()) { + callback(Result::Success, value.get()); + } else if (value.is()) { + callback(Result::Success, value.get()); + } else { + callback(Result::WrongType, {}); + } + } else { + callback(result, {}); + } + }; + get_param_async(name, callback_future_result, cookie); +} + void MavlinkParameterClient::get_param_float_async( const std::string& name, const GetParamFloatCallback& callback, const void* cookie) {