Skip to content

Commit

Permalink
core: Fix reading int8/16 params from ArduPilot
Browse files Browse the repository at this point in the history
When reading one-by-one with get_param_int
  • Loading branch information
pavloblindnology committed Sep 12, 2024
1 parent 2de3994 commit 846d1fc
Showing 1 changed file with 23 additions and 0 deletions.
23 changes: 23 additions & 0 deletions src/mavsdk/core/mavlink_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,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<int32_t> 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<int32_t>()) {
callback(Result::Success, value.get<int32_t>());
} else if (value.is<int16_t>()) {
callback(Result::Success, value.get<int16_t>());
} else if (value.is<int8_t>()) {
callback(Result::Success, value.get<int8_t>());
} 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)
{
Expand Down

0 comments on commit 846d1fc

Please sign in to comment.