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

Getting UINT16 param from ArduPilot doesn't work #2396

Closed
pavloblindnology opened this issue Sep 10, 2024 · 7 comments · Fixed by #2400
Closed

Getting UINT16 param from ArduPilot doesn't work #2396

pavloblindnology opened this issue Sep 10, 2024 · 7 comments · Fixed by #2400
Labels

Comments

@pavloblindnology
Copy link
Contributor

Cannot read any param from ArduPilot other than float and int32 - say RC1_MIN (int16).
Aftere debugging I can see that the problem is in mavlink_parameter_client::get_param_async_typesafe function.
Before it parameter is succesfully read. But checking its type (int16_t vs int32_t) doesn't pass here

@julianoes
Copy link
Collaborator

Does ArduPilot use uint16 params? Could you help me reproduce the issue?

@julianoes julianoes added the bug label Sep 10, 2024
@pavloblindnology
Copy link
Contributor Author

Does ArduPilot use uint16 params? Could you help me reproduce the issue?

No, AP supports only int8, int16, int32 and float params.
To reproduce the bug just try to read any int16 param (say RC1_MIN) with any get_param_int method (say mavsdk::Param::get_param_int).

I've fixed this by specializing template method MavlinkParameterClient::get_param_async_typesafe like this

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);
}

@julianoes
Copy link
Collaborator

Given you have code to fix it @pavloblindnology, do you want to create a pull request to contribute it? That would be great.

@pavloblindnology
Copy link
Contributor Author

Sure, why not. If it looks plausible to you.

@pavloblindnology
Copy link
Contributor Author

@julianoes Access denied while pushing PR branch.

@JonasVautherin
Copy link
Collaborator

@pavloblindnology: you need to create a fork, push your branch to your fork, and open a PR to this repo 👍

@pavloblindnology
Copy link
Contributor Author

@JonasVautherin Please note that I also created backport v2.12 PR #2401.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging a pull request may close this issue.

3 participants