Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[BACKPORT v2.12] core: Fix reading int8/16 params from ArduPilot #2401

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@ -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<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
Loading