mavlink / MAVSDK

API and library for MAVLink compatible systems written in C++17
https://mavsdk.mavlink.io
BSD 3-Clause "New" or "Revised" License
627 stars 507 forks source link

Unknown type: bool (param_value.cpp:317) error #2046

Closed tlapik123 closed 1 year ago

tlapik123 commented 1 year ago

I'm getting the Unknown type: bool (param_value.cpp:317) when running the camera example.

I think, I've identified the issue.

As stated here: https://mavlink.io/en/services/camera_def.html#parameter-types the bool type in the camera definition should be supported.

the code in param_value.cpp:

if (strcmp(type_str.c_str(), "uint8") == 0) {
        _value = static_cast<uint8_t>(std::stoi(value_str));
    } else if (strcmp(type_str.c_str(), "int8") == 0) {
        _value = static_cast<int8_t>(std::stoi(value_str));
    } else if (strcmp(type_str.c_str(), "uint16") == 0) {
        _value = static_cast<uint16_t>(std::stoi(value_str));
    } else if (strcmp(type_str.c_str(), "int16") == 0) {
        _value = static_cast<int16_t>(std::stoi(value_str));
    } else if (strcmp(type_str.c_str(), "uint32") == 0) {
        _value = static_cast<uint32_t>(std::stoi(value_str));
    } else if (strcmp(type_str.c_str(), "int32") == 0) {
        _value = static_cast<int32_t>(std::stoi(value_str));
    } else if (strcmp(type_str.c_str(), "uint64") == 0) {
        _value = static_cast<uint64_t>(std::stoll(value_str));
    } else if (strcmp(type_str.c_str(), "int64") == 0) {
        _value = static_cast<int64_t>(std::stoll(value_str));
    } else if (strcmp(type_str.c_str(), "float") == 0) {
        _value = static_cast<float>(std::stof(value_str));
    } else if (strcmp(type_str.c_str(), "double") == 0) {
        _value = static_cast<double>(std::stod(value_str));
    } else {
        LogErr() << "Unknown type: " << type_str;
        return false;
    }
    return true;

It also throws the error Unknown type attribute: bool (camera_definition.cpp:130) Which I'm not sure if its a separate issue or fixed by modifying the above code.

Just a sidenote - why is the strcmp used here when we have std::string? Why not use ==?

julianoes commented 1 year ago

Good points.

According to the MAVLink enum there is no bool (see https://mavlink.io/en/messages/common.html#MAV_PARAM_EXT_TYPE) even though the docs say that. I would probably suggest to just use uint8_t, and I'll try to change the docs because that's confusing.

Regarding strcmp, that's indeed ugly, I'll change it.

julianoes commented 1 year ago

Given there seem to be xml files out there containing bool, we have to support it and can't just remove it from the spec at this point. I'll try to find a fix in MAVSDK.

julianoes commented 1 year ago

Can you try out https://github.com/mavlink/MAVSDK/pull/2048 and check if it fixes your problem?

tlapik123 commented 1 year ago

I'm sorry I'm unable to test this at this moment, but I'll tell you in 3 days. Thank you very much for your time btw.

tlapik123 commented 1 year ago

Can you try out #2048 and check if it fixes your problem?

I can confirm this fixes the problem. Thank you.

tlapik123 commented 1 year ago

Ok, it didn't fix everything as I initially thought. The type="bool" parameters aren't required to have options (or range). As per documentation

The simplest parameter would be a boolean type, which inherently (and automatically) only provides two options (on/off).

In the camera_definitions xml file I have:

    <parameter name="IMG_RAD_TIFF" type="bool" default="0">
        <description>Take radiometric TIFF</description>
    </parameter>

When I launch the camera example i get the following error and warn:

[09:35:01|Error] min range missing for IMG_RAD_TIFF (camera_definition.cpp:344)
[09:35:01|Warn ] Not found: IMG_RAD_TIFF (camera_definition.cpp:219)

I've looked into the code and the problem arises because in camera_definition.cpp:199 a check for "options" child element fails and the range is subsequently not found.

Just a sidenote is there any checker (or formal definition) for the validity of camera_definition xml file? Since the only references are the documentation and the example. Neither of which have a mention of min and max values that are supported by the code (and in some .xml files that I have seen).

julianoes commented 1 year ago

It would be great if you could make a pull request to fix the min range issue.

I don't think there is a formal schema, it's just the docs here: https://mavlink.io/en/services/camera_def.html A schema check would be nice, feel free to contribute it.

tlapik123 commented 1 year ago

It would be great if you could make a pull request to fix the min range issue.

Good point, I have created a PR #2056.

I don't think there is a formal schema, it's just the docs here: https://mavlink.io/en/services/camera_def.html A schema check would be nice, feel free to contribute it.

Frankly, I don't know if proper schema is even possible since the documentation is a subset of what the code does (and what the users rely on). But if you think it would be beneficial to at least have something I might give it a shot.