APMParameterMetaData.cc 25.5 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10

11
#include "APMParameterMetaData.h"
12 13 14 15 16 17 18
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"

#include <QFile>
#include <QFileInfo>
#include <QDir>
#include <QDebug>
Don Gagne's avatar
Don Gagne committed
19
#include <QStack>
20

Gus Grubba's avatar
Gus Grubba committed
21 22
static const char* kInvalidConverstion = "Internal Error: No support for string parameters";

23 24
QGC_LOGGING_CATEGORY(APMParameterMetaDataLog,           "APMParameterMetaDataLog")
QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog,    "APMParameterMetaDataVerboseLog")
25

26 27
APMParameterMetaData::APMParameterMetaData(void)
    : _parameterMetaDataLoaded(false)
28
{
Don Gagne's avatar
Don Gagne committed
29

30 31 32 33 34 35 36
}

/// Converts a string to a typed QVariant
///     @param string String to convert
///     @param type Type for Fact which dictates the QVariant type as well
///     @param convertOk Returned: true: conversion success, false: conversion failure
/// @return Returns the correctly type QVariant
37 38
QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string,
                                                     FactMetaData::ValueType_t type, bool* convertOk)
39 40 41 42 43
{
    QVariant var(string);

    int convertTo = QVariant::Int; // keep compiler warning happy
    switch (type) {
Don Gagne's avatar
Don Gagne committed
44 45 46
    case FactMetaData::valueTypeUint8:
    case FactMetaData::valueTypeUint16:
    case FactMetaData::valueTypeUint32:
47
    case FactMetaData::valueTypeUint64:
Don Gagne's avatar
Don Gagne committed
48 49 50 51 52
        convertTo = QVariant::UInt;
        break;
    case FactMetaData::valueTypeInt8:
    case FactMetaData::valueTypeInt16:
    case FactMetaData::valueTypeInt32:
53
    case FactMetaData::valueTypeInt64:
Don Gagne's avatar
Don Gagne committed
54 55 56 57 58
        convertTo = QVariant::Int;
        break;
    case FactMetaData::valueTypeFloat:
        convertTo = QMetaType::Float;
        break;
59
    case FactMetaData::valueTypeElapsedTimeInSeconds:
Don Gagne's avatar
Don Gagne committed
60 61 62 63
    case FactMetaData::valueTypeDouble:
        convertTo = QVariant::Double;
        break;
    case FactMetaData::valueTypeString:
Gus Grubba's avatar
Gus Grubba committed
64
        qWarning() << kInvalidConverstion;
Don Gagne's avatar
Don Gagne committed
65 66
        convertTo = QVariant::String;
        break;
67
    case FactMetaData::valueTypeBool:
Gus Grubba's avatar
Gus Grubba committed
68
        qWarning() << kInvalidConverstion;
69 70
        convertTo = QVariant::Bool;
        break;
Gus Grubba's avatar
Gus Grubba committed
71 72 73 74
    case FactMetaData::valueTypeCustom:
        qWarning() << kInvalidConverstion;
        convertTo = QVariant::ByteArray;
        break;
75
    }
76

77
    *convertOk = var.convert(convertTo);
78

79 80 81
    return var;
}

82 83 84 85 86 87
QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum)
{
    QString vehicleName;

    switch(vehicleTypeEnum) {
        case MAV_TYPE_FIXED_WING:
88 89 90 91 92 93 94
        case MAV_TYPE_VTOL_DUOROTOR:
        case MAV_TYPE_VTOL_QUADROTOR:
        case MAV_TYPE_VTOL_TILTROTOR:
        case MAV_TYPE_VTOL_RESERVED2:
        case MAV_TYPE_VTOL_RESERVED3:
        case MAV_TYPE_VTOL_RESERVED4:
        case MAV_TYPE_VTOL_RESERVED5:
95 96 97 98 99 100 101 102 103 104 105 106
            vehicleName = "ArduPlane";
            break;
        case MAV_TYPE_QUADROTOR:
        case MAV_TYPE_COAXIAL:
        case MAV_TYPE_HELICOPTER:
        case MAV_TYPE_HEXAROTOR:
        case MAV_TYPE_OCTOROTOR:
        case MAV_TYPE_TRICOPTER:
            vehicleName = "ArduCopter";
            break;
        case MAV_TYPE_ANTENNA_TRACKER:
            vehicleName = "Antenna Tracker";
Gus Grubba's avatar
Gus Grubba committed
107
            break;
108 109 110 111 112 113 114 115
        case MAV_TYPE_GENERIC:
        case MAV_TYPE_GCS:
        case MAV_TYPE_AIRSHIP:
        case MAV_TYPE_FREE_BALLOON:
        case MAV_TYPE_ROCKET:
            break;
        case MAV_TYPE_GROUND_ROVER:
        case MAV_TYPE_SURFACE_BOAT:
Don Gagne's avatar
Don Gagne committed
116
            vehicleName = "APMrover2";
117
            break;
118 119 120
        case MAV_TYPE_SUBMARINE:
            vehicleName = "ArduSub";
            break;
121 122 123 124 125 126 127 128 129 130 131
        case MAV_TYPE_FLAPPING_WING:
        case MAV_TYPE_KITE:
        case MAV_TYPE_ONBOARD_CONTROLLER:
        case MAV_TYPE_GIMBAL:
        case MAV_TYPE_ENUM_END:
        default:
            break;
    }
    return vehicleName;
}

132 133 134 135 136 137 138
QString APMParameterMetaData::_groupFromParameterName(const QString& name)
{
    QString group = name.split('_').first();
    return group.remove(QRegExp("[0-9]*$")); // remove any numbers from the end
}


Don Gagne's avatar
Don Gagne committed
139
void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile)
140 141 142 143 144 145
{
    if (_parameterMetaDataLoaded) {
        return;
    }
    _parameterMetaDataLoaded = true;

146
    QRegExp parameterCategories = QRegExp("ArduCopter|ArduPlane|APMrover2|ArduSub|AntennaTracker");
147 148
    QString currentCategory;

Don Gagne's avatar
Don Gagne committed
149
    qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << metaDataFile;
150

Don Gagne's avatar
Don Gagne committed
151
    QFile xmlFile(metaDataFile);
152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
    Q_ASSERT(xmlFile.exists());

    bool success = xmlFile.open(QIODevice::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);

    QXmlStreamReader xml(xmlFile.readAll());
    xmlFile.close();
    if (xml.hasError()) {
        qCWarning(APMParameterMetaDataLog) << "Badly formed XML, reading failed: " << xml.errorString();
        return;
    }

    bool                badMetaData = true;
    QStack<int>         xmlState;
167
    APMFactMetaDataRaw* rawMetaData = nullptr;
168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215

    xmlState.push(XmlStateNone);

    QMap<QString,QStringList> groupMembers; //used to remove groups with single item

    while (!xml.atEnd()) {
        if (xml.isStartElement()) {
            QString elementName = xml.name().toString();

            if (elementName.isEmpty()) {
                // skip empty elements
            } else if (elementName == "paramfile") {
                if (xmlState.top() != XmlStateNone) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, paramfile matched";
                }
                xmlState.push(XmlstateParamFileFound);
                // we don't really do anything with this element
            } else if (elementName == "vehicles") {
                if (xmlState.top() != XmlstateParamFileFound) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, vehicles matched";
                    return;
                }
                xmlState.push(XmlStateFoundVehicles);
            } else if (elementName == "libraries") {
                if (xmlState.top() != XmlstateParamFileFound) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, libraries matched";
                    return;
                }
                currentCategory = "libraries";
                xmlState.push(XmlStateFoundLibraries);
            } else if (elementName == "parameters") {
                if (xmlState.top() != XmlStateFoundVehicles && xmlState.top() != XmlStateFoundLibraries) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameters matched"
                                                       << "but we don't have proper vehicle or libraries yet";
                    return;
                }

                if (xml.attributes().hasAttribute("name")) {
                    // we will handle metadata only for specific MAV_TYPEs and libraries
                    const QString nameValue = xml.attributes().value("name").toString();
                    if (nameValue.contains(parameterCategories)) {
                        xmlState.push(XmlStateFoundParameters);
                        currentCategory = nameValue;
                    } else if(xmlState.top() == XmlStateFoundLibraries) {
                        // we handle all libraries section under the same category libraries
                        // so not setting currentCategory
                        xmlState.push(XmlStateFoundParameters);
                    } else {
216
                        qCDebug(APMParameterMetaDataVerboseLog) << "not interested in this block of parameters, skipping:" << nameValue;
217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241
                        if (skipXMLBlock(xml, "parameters")) {
                            qCWarning(APMParameterMetaDataLog) << "something wrong with the xml, skip of the xml failed";
                            return;
                        }
                        xml.readNext();
                        continue;
                    }
                }
            }  else if (elementName == "param") {
                if (xmlState.top() != XmlStateFoundParameters) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, element param matched"
                                                       << "while we are not yet in parameters";
                    return;
                }
                xmlState.push(XmlStateFoundParameter);

                if (!xml.attributes().hasAttribute("name")) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameter attribute name missing";
                    return;
                }

                QString name = xml.attributes().value("name").toString();
                if (name.contains(':')) {
                    name = name.split(':').last();
                }
242
                QString group = _groupFromParameterName(name);
243

244 245 246 247 248
                QString category = xml.attributes().value("user").toString();
                if (category.isEmpty()) {
                    category = QStringLiteral("Advanced");
                }

249
                QString shortDescription = xml.attributes().value("humanName").toString();
250
                QString longDescription = xml.attributes().value("documentation").toString();
251

252
                qCDebug(APMParameterMetaDataVerboseLog) << "Found parameter name:" << name
253 254
                          << "short Desc:" << shortDescription
                          << "longDescription:" << longDescription
255
                          << "category: " << category
256 257 258 259
                          << "group: " << group;

                Q_ASSERT(!rawMetaData);
                if (_vehicleTypeToParametersMap[currentCategory].contains(name)) {
260 261
                    qCDebug(APMParameterMetaDataLog) << "Duplicate parameter found:" << name;
                    rawMetaData = _vehicleTypeToParametersMap[currentCategory][name];
262
                } else {
263
                    rawMetaData = new APMFactMetaDataRaw(this);
264 265 266
                    _vehicleTypeToParametersMap[currentCategory][name] = rawMetaData;
                    groupMembers[group] << name;
                }
267 268
                qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name;
                rawMetaData->name = name;
269
                rawMetaData->category = category;
270 271 272
                rawMetaData->group = group;
                rawMetaData->shortDescription = shortDescription;
                rawMetaData->longDescription = longDescription;
273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292
            } else {
                // We should be getting meta data now
                if (xmlState.top() != XmlStateFoundParameter) {
                    qCWarning(APMParameterMetaDataLog) << "Badly formed XML, while reading parameter fields wrong state";
                    return;
                }
                if (!badMetaData) {
                    if (!parseParameterAttributes(xml, rawMetaData)) {
                        qCDebug(APMParameterMetaDataLog) << "Badly formed XML, failed to read parameter attributes";
                        return;
                    }
                    continue;
                }
            }
        } else if (xml.isEndElement()) {
            QString elementName = xml.name().toString();

            if (elementName == "param" && xmlState.top() == XmlStateFoundParameter) {
                // Done loading this parameter
                // Reset for next parameter
293
                qCDebug(APMParameterMetaDataVerboseLog) << "done loading parameter";
294
                rawMetaData = nullptr;
295 296 297
                badMetaData = false;
                xmlState.pop();
            } else if (elementName == "parameters") {
298
                qCDebug(APMParameterMetaDataVerboseLog) << "end of parameters for category: " << currentCategory;
299 300 301 302
                correctGroupMemberships(_vehicleTypeToParametersMap[currentCategory], groupMembers);
                groupMembers.clear();
                xmlState.pop();
            } else if (elementName == "vehicles") {
303
                qCDebug(APMParameterMetaDataVerboseLog) << "vehicles end here, libraries will follow";
304 305 306 307 308 309 310 311 312 313 314 315 316
                xmlState.pop();
            }
        }
        xml.readNext();
    }
}

void APMParameterMetaData::correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap,
                                                   QMap<QString,QStringList>& groupMembers)
{
    foreach(const QString& groupName, groupMembers.keys()) {
            if (groupMembers[groupName].count() == 1) {
                foreach(const QString& parameter, groupMembers.value(groupName)) {
317
                    parameterToFactMetaDataMap[parameter]->group = FactMetaData::defaultGroup();
318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339
                }
            }
        }
}

bool APMParameterMetaData::skipXMLBlock(QXmlStreamReader& xml, const QString& blockName)
{
    QString elementName;
    do {
        xml.readNext();
        elementName = xml.name().toString();
    } while ((elementName != blockName) && (xml.isEndElement()));
    return !xml.isEndDocument();
}

bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw* rawMetaData)
{
    QString elementName = xml.name().toString();
    QList<QPair<QString,QString> > values;
    // as long as param doens't end
    while (!(elementName == "param" && xml.isEndElement())) {
        if (elementName.isEmpty()) {
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
340
            // skip empty elements. Somehow I am getting lot of these. Don't know what to do with them.
341 342
        } else if (elementName == "field") {
            QString attributeName = xml.attributes().value("name").toString();
343

344 345 346 347
            if ( attributeName == "Range") {
                QString range = xml.readElementText().trimmed();
                QStringList rangeList = range.split(' ');
                if (rangeList.count() != 2) {
348
                    qCDebug(APMParameterMetaDataVerboseLog) << "space seperator didn't work',trying 'to' separator";
349 350
                    rangeList = range.split("to");
                    if (rangeList.count() != 2) {
351
                        qCDebug(APMParameterMetaDataVerboseLog) << " 'to' seperaator didn't work', trying '-' as seperator";
352 353
                        rangeList = range.split('-');
                        if (rangeList.count() != 2) {
354
                            qCDebug(APMParameterMetaDataLog) << "something wrong with range, all three separators have failed" << range;
355 356 357 358
                        }
                    }
                }

359 360 361 362 363 364 365 366 367 368 369 370
                // everything should be good. lets collect min and max
                if (rangeList.count() == 2) {
                    rawMetaData->min = rangeList.first().trimmed();
                    rawMetaData->max = rangeList.last().trimmed();

                    // sanitize min and max off any comments that they may have
                    if (rawMetaData->min.contains(' ')) {
                        rawMetaData->min = rawMetaData->min.split(' ').first();
                    }
                    if(rawMetaData->max.contains(' ')) {
                        rawMetaData->max = rawMetaData->max.split(' ').first();
                    }
371
                    qCDebug(APMParameterMetaDataVerboseLog) << "read field parameter " << "min: " << rawMetaData->min
372
                                                     << "max: " << rawMetaData->max;
373 374 375
                }
            } else if (attributeName == "Increment") {
                QString increment = xml.readElementText();
376
                qCDebug(APMParameterMetaDataVerboseLog) << "read Increment: " << increment;
377 378 379
                rawMetaData->incrementSize = increment;
            } else if (attributeName == "Units") {
                QString units = xml.readElementText();
380
                qCDebug(APMParameterMetaDataVerboseLog) << "read Units: " << units;
381
                rawMetaData->units = units;
382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403
            } else if (attributeName == "Bitmask") {
                bool    parseError = false;

                QString bitmaskString = xml.readElementText();
                qCDebug(APMParameterMetaDataVerboseLog) << "read Bitmask: " << bitmaskString;
                QStringList bitmaskList = bitmaskString.split(",");
                if (bitmaskList.count() > 0) {
                    foreach (const QString& bitmask, bitmaskList) {
                        QStringList pair = bitmask.split(":");
                        if (pair.count() == 2) {
                            rawMetaData->bitmask << QPair<QString, QString>(pair[0], pair[1]);
                        } else {
                            qCDebug(APMParameterMetaDataLog) << "parse error: bitmask:" << bitmaskString << "pair count:" << pair.count();
                            parseError = true;
                            break;
                        }
                    }
                }

                if (parseError) {
                    rawMetaData->bitmask.clear();
                }
404 405 406 407 408
            } else if (attributeName == "RebootRequired") {
                QString strValue = xml.readElementText().trimmed();
                if (strValue.compare("true", Qt::CaseInsensitive) == 0) {
                    rawMetaData->rebootRequired = true;
                }
409 410 411 412 413 414
            }
        } else if (elementName == "values") {
            // doing nothing individual value will follow anyway. May be used for sanity checking.
        } else if (elementName == "value") {
            QString valueValue = xml.attributes().value("code").toString();
            QString valueName = xml.readElementText();
415
            qCDebug(APMParameterMetaDataVerboseLog) << "read value parameter " << "value desc: "
416 417 418 419 420 421 422 423 424 425
                                             << valueName << "code: " << valueValue;
            values << QPair<QString,QString>(valueValue, valueName);
            rawMetaData->values = values;
        } else {
            qCWarning(APMParameterMetaDataLog) << "Unknown parameter element in XML: " << elementName;
        }
        xml.readNext();
        elementName = xml.name().toString();
    }
    return true;
426 427
}

428
FactMetaData* APMParameterMetaData::getMetaDataForFact(const QString& name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type)
429
{
430
    const QString mavTypeString = mavTypeToString(vehicleType);
431
    APMFactMetaDataRaw* rawMetaData = nullptr;
432 433

    // check if we have metadata for fact, use generic otherwise
434 435 436 437
    if (_vehicleTypeToParametersMap[mavTypeString].contains(name)) {
        rawMetaData = _vehicleTypeToParametersMap[mavTypeString][name];
    } else if (_vehicleTypeToParametersMap["libraries"].contains(name)) {
        rawMetaData = _vehicleTypeToParametersMap["libraries"][name];
438 439
    }

440
    FactMetaData *metaData = new FactMetaData(type, this);
441 442 443

    // we don't have data for this fact
    if (!rawMetaData) {
444
        metaData->setCategory(QStringLiteral("Advanced"));
445 446 447
        metaData->setGroup(_groupFromParameterName(name));
        qCDebug(APMParameterMetaDataLog) << "No metaData for " << name << "using generic metadata";
        return metaData;
448 449 450
    }

    metaData->setName(rawMetaData->name);
451
    metaData->setCategory(rawMetaData->category);
452
    metaData->setGroup(rawMetaData->group);
453
    metaData->setVehicleRebootRequired(rawMetaData->rebootRequired);
454 455 456 457 458 459 460 461 462 463

    if (!rawMetaData->shortDescription.isEmpty()) {
        metaData->setShortDescription(rawMetaData->shortDescription);
    }

    if (!rawMetaData->longDescription.isEmpty()) {
        metaData->setLongDescription(rawMetaData->longDescription);
    }

    if (!rawMetaData->units.isEmpty()) {
464
        metaData->setRawUnits(rawMetaData->units);
465 466 467 468 469
    }

    if (!rawMetaData->min.isEmpty()) {
        QVariant varMin;
        QString errorString;
470 471
        if (metaData->convertAndValidateRaw(rawMetaData->min, false /* validate as well */, varMin, errorString)) {
            metaData->setRawMin(varMin);
472 473 474 475 476 477 478 479 480 481
        } else {
            qCDebug(APMParameterMetaDataLog) << "Invalid min value, name:" << metaData->name()
                                             << " type:" << metaData->type() << " min:" << rawMetaData->min
                                             << " error:" << errorString;
        }
    }

    if (!rawMetaData->max.isEmpty()) {
        QVariant varMax;
        QString errorString;
482 483
        if (metaData->convertAndValidateRaw(rawMetaData->max, false /* validate as well */, varMax, errorString)) {
            metaData->setRawMax(varMax);
484 485 486 487 488 489
        } else {
            qCDebug(APMParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:"
                                             << metaData->type() << " max:" << rawMetaData->max
                                             << " error:" << errorString;
        }
    }
490

Don Gagne's avatar
Don Gagne committed
491 492 493 494 495 496 497 498 499
    if (rawMetaData->values.count() > 0) {
        QStringList     enumStrings;
        QVariantList    enumValues;

        for (int i=0; i<rawMetaData->values.count(); i++) {
            QVariant    enumValue;
            QString     errorString;
            QPair<QString, QString> enumPair = rawMetaData->values[i];

500
            if (metaData->convertAndValidateRaw(enumPair.first, false /* validate */, enumValue, errorString)) {
Don Gagne's avatar
Don Gagne committed
501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517
                enumValues << enumValue;
                enumStrings << enumPair.second;
            } else {
                qCDebug(APMParameterMetaDataLog) << "Invalid enum value, name:" << metaData->name()
                                                 << " type:" << metaData->type() << " value:" << enumPair.first
                                                 << " error:" << errorString;
                enumStrings.clear();
                enumValues.clear();
                break;
            }
        }

        if (enumStrings.count() != 0) {
            metaData->setEnumInfo(enumStrings, enumValues);
        }
    }

518 519 520 521 522 523 524 525 526 527 528 529
    if (rawMetaData->bitmask.count() > 0) {
        QStringList     bitmaskStrings;
        QVariantList    bitmaskValues;

        for (int i=0; i<rawMetaData->bitmask.count(); i++) {
            QVariant    bitmaskValue;
            QString     errorString;
            QPair<QString, QString> bitmaskPair = rawMetaData->bitmask[i];

            bool ok = false;
            unsigned int bitSet = bitmaskPair.first.toUInt(&ok);
            bitSet = 1 << bitSet;
530 531 532

            QVariant typedBitSet;

533
            switch (type) {
534 535 536 537 538 539 540 541 542
            case FactMetaData::valueTypeInt8:
                typedBitSet = QVariant((signed char)bitSet);
                break;

            case FactMetaData::valueTypeInt16:
                typedBitSet = QVariant((short int)bitSet);
                break;

            case FactMetaData::valueTypeInt32:
543
            case FactMetaData::valueTypeInt64:
544 545 546 547 548 549
                typedBitSet = QVariant((int)bitSet);
                break;

            case FactMetaData::valueTypeUint8:
            case FactMetaData::valueTypeUint16:
            case FactMetaData::valueTypeUint32:
550
            case FactMetaData::valueTypeUint64:
551 552 553 554 555 556 557 558 559 560 561
                typedBitSet = QVariant(bitSet);
                break;

            default:
                break;
            }
            if (typedBitSet.isNull()) {
                qCDebug(APMParameterMetaDataLog) << "Invalid type for bitmask, name:" << metaData->name()
                                                 << " type:" << metaData->type();
            }

562 563
            if (!ok) {
                qCDebug(APMParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name()
564 565
                                                 << " type:" << metaData->type() << " value:" << bitSet
                                                 << " error: toUInt failed";
566 567 568 569 570
                bitmaskStrings.clear();
                bitmaskValues.clear();
                break;
            }

571
            if (metaData->convertAndValidateRaw(typedBitSet, false /* validate */, bitmaskValue, errorString)) {
572 573 574 575
                bitmaskValues << bitmaskValue;
                bitmaskStrings << bitmaskPair.second;
            } else {
                qCDebug(APMParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name()
576
                                                 << " type:" << metaData->type() << " value:" << typedBitSet
577 578 579 580 581 582 583 584 585 586 587 588
                                                 << " error:" << errorString;
                bitmaskStrings.clear();
                bitmaskValues.clear();
                break;
            }
        }

        if (bitmaskStrings.count() != 0) {
            metaData->setBitmaskInfo(bitmaskStrings, bitmaskValues);
        }
    }

Don Gagne's avatar
Don Gagne committed
589 590 591 592 593
    if (!rawMetaData->incrementSize.isEmpty()) {
        double  increment;
        bool    ok;
        increment = rawMetaData->incrementSize.toDouble(&ok);
        if (ok) {
594
            metaData->setRawIncrement(increment);
Don Gagne's avatar
Don Gagne committed
595 596 597 598 599
        } else {
            qCDebug(APMParameterMetaDataLog) << "Invalid value for increment, name:" << metaData->name() << " increment:" << rawMetaData->incrementSize;
        }
    }

600
    // ArduPilot does not yet support decimal places meta data. So for P/I/D parameters we force to 6 places
601 602 603 604 605
    if ((name.endsWith(QStringLiteral("_P")) ||
         name.endsWith(QStringLiteral("_I")) ||
         name.endsWith(QStringLiteral("_D"))) &&
            (type == FactMetaData::valueTypeFloat ||
             type == FactMetaData::valueTypeDouble)) {
606 607 608
        metaData->setDecimalPlaces(6);
    }

609
    return metaData;
610
}
611 612 613 614 615

void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{
    majorVersion = -1;
    minorVersion = -1;
Don Gagne's avatar
Don Gagne committed
616 617 618 619 620 621

    // Meta data version is hacked in for now based on file name
    QRegExp regExp(".*\\.(\\d)\\.(\\d)\\.xml$");
    if (regExp.exactMatch(metaDataFile) && regExp.captureCount() == 2) {
        majorVersion = regExp.cap(2).toInt();
        minorVersion = 0;
622 623
    } else {
        qWarning() << QStringLiteral("Unable to parse version from parameter meta data file name: '%1'").arg(metaDataFile);
Don Gagne's avatar
Don Gagne committed
624
    }
625
}