ParameterLoader.cc 42.1 KB
Newer Older
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
dogmaphobic's avatar
dogmaphobic committed
13

14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
dogmaphobic's avatar
dogmaphobic committed
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

22 23 24 25 26 27 28 29
 ======================================================================*/

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "ParameterLoader.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
30
#include "QGCApplication.h"
31
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
32
#include "FirmwarePlugin.h"
33
#include "UAS.h"
34 35 36 37

#include <QFile>
#include <QDebug>

38 39 40 41 42
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;

43
QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
44

Don Gagne's avatar
Don Gagne committed
45 46
Fact ParameterLoader::_defaultFact;

Don Gagne's avatar
Don Gagne committed
47
const char* ParameterLoader::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
48 49 50

ParameterLoader::ParameterLoader(Vehicle* vehicle)
    : QObject(vehicle)
51 52
    , _vehicle(vehicle)
    , _mavlink(qgcApp()->toolbox()->mavlinkProtocol())
53
    , _dedicatedLink(_vehicle->priorityLink())
54 55
    , _parametersReady(false)
    , _initialLoadComplete(false)
56
    , _saveRequired(false)
57
    , _defaultComponentId(FactSystem::defaultComponentId)
58 59
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
60
    , _totalParamCount(0)
61
{
62
    Q_ASSERT(_vehicle);
63
    Q_ASSERT(_mavlink);
dogmaphobic's avatar
dogmaphobic committed
64

65 66
    // We signal this to ouselves in order to start timer on our thread
    connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
dogmaphobic's avatar
dogmaphobic committed
67

68 69 70 71
    _initialRequestTimeoutTimer.setSingleShot(true);
    _initialRequestTimeoutTimer.setInterval(6000);
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_initialRequestTimeout);

72
    _waitingParamTimeoutTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
73
    _waitingParamTimeoutTimer.setInterval(1000);
74
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
75

76
    connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterLoader::_parameterUpdate);
77

78 79 80
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();
    _defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();

81 82 83
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
    refreshAllParameters();
84 85 86 87
}

ParameterLoader::~ParameterLoader()
{
88
    delete _parameterMetaData;
89 90 91
}

/// Called whenever a parameter is updated or first seen.
92
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
93 94
{
    // Is this for our uas?
95
    if (uasId != _vehicle->id()) {
96 97
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
98

99 100
    _initialRequestTimeoutTimer.stop();

101 102 103 104 105 106 107 108
    qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
                                    "componentId:" << componentId <<
                                    "name:" << parameterName <<
                                    "count:" << parameterCount <<
                                    "index:" << parameterId <<
                                    "mavType:" << mavType <<
                                    "value:" << value <<
                                    ")";
dogmaphobic's avatar
dogmaphobic committed
109

110 111 112 113 114 115 116 117
#if 0
    // Handy for testing retry logic
    static int counter = 0;
    if (counter++ & 0x3) {
        qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
        return;
    }
#endif
118 119 120

    if (parameterName == "_HASH_CHECK") {
        /* we received a cache hash, potentially load from cache */
121
        _tryCacheHashLoad(uasId, componentId, value);
122 123
        return;
    }
124
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
125

126 127
    // Restart our waiting for param timer
    _waitingParamTimeoutTimer.start();
dogmaphobic's avatar
dogmaphobic committed
128

129 130 131 132 133
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
134 135

    _mapParameterId2Name[componentId][parameterId] = parameterName;
dogmaphobic's avatar
dogmaphobic committed
136

137 138
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
139 140 141 142
        // Add all indices to the wait list, parameter index is 0-based
        for (int waitingIndex=0; waitingIndex<parameterCount; waitingIndex++) {
            // This will add the new component id, as well as the the new waiting index and set the retry count for that index to 0
            _waitingReadParamIndexMap[componentId][waitingIndex] = 0;
143
        }
dogmaphobic's avatar
dogmaphobic committed
144

145 146 147
        // The read and write waiting lists for this component are initialized the empty
        _waitingReadParamNameMap[componentId] = QMap<QString, int>();
        _waitingWriteParamNameMap[componentId] = QMap<QString, int>();
dogmaphobic's avatar
dogmaphobic committed
148

149 150
        qCDebug(ParameterLoaderLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
    }
dogmaphobic's avatar
dogmaphobic committed
151

152
    // Remove this parameter from the waiting lists
153 154 155
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
156
    qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
157 158 159 160
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

    // Track how many parameters we are still waiting for
dogmaphobic's avatar
dogmaphobic committed
161

162 163 164
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
165

166 167 168 169 170 171 172
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

dogmaphobic's avatar
dogmaphobic committed
173

174 175 176 177 178 179
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
180

181 182 183 184 185 186
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
187

188 189 190 191 192 193 194 195 196 197 198 199 200 201
    int waitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount + waitingWriteParamNameCount;
    if (waitingParamCount) {
        qCDebug(ParameterLoaderLog) << "waitingParamCount:" << waitingParamCount;
    } else {
        // No more parameters to wait for, stop the timeout
        _waitingParamTimeoutTimer.stop();
    }

    // Update progress bar
    if (waitingParamCount == 0) {
        emit parameterListProgress(0);
    } else {
        emit parameterListProgress((float)(_totalParamCount - waitingParamCount) / (float)_totalParamCount);
    }
dogmaphobic's avatar
dogmaphobic committed
202

203
    // Determine default component id
204 205 206
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        _defaultComponentId = componentId;
    }
dogmaphobic's avatar
dogmaphobic committed
207

208 209 210 211 212
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

213
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
214
        qCDebug(ParameterLoaderLog) << "Adding new fact";
dogmaphobic's avatar
dogmaphobic committed
215

216 217 218 219 220 221
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
222
                factType = FactMetaData::valueTypeInt8;
223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246
                break;
            case MAV_PARAM_TYPE_UINT16:
                factType = FactMetaData::valueTypeUint16;
                break;
            case MAV_PARAM_TYPE_INT16:
                factType = FactMetaData::valueTypeInt16;
                break;
            case MAV_PARAM_TYPE_UINT32:
                factType = FactMetaData::valueTypeUint32;
                break;
            case MAV_PARAM_TYPE_INT32:
                factType = FactMetaData::valueTypeInt32;
                break;
            case MAV_PARAM_TYPE_REAL32:
                factType = FactMetaData::valueTypeFloat;
                break;
            case MAV_PARAM_TYPE_REAL64:
                factType = FactMetaData::valueTypeDouble;
                break;
            default:
                factType = FactMetaData::valueTypeInt32;
                qCritical() << "Unsupported fact type" << mavType;
                break;
        }
dogmaphobic's avatar
dogmaphobic committed
247

248
        Fact* fact = new Fact(componentId, parameterName, factType, this);
dogmaphobic's avatar
dogmaphobic committed
249

250
        _mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
dogmaphobic's avatar
dogmaphobic committed
251

252
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
Don Gagne's avatar
Don Gagne committed
253
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated);
254
    }
dogmaphobic's avatar
dogmaphobic committed
255

Don Gagne's avatar
Don Gagne committed
256 257
    _dataMutex.unlock();

258
    Q_ASSERT(_mapParameterName2Variant[componentId].contains(parameterName));
dogmaphobic's avatar
dogmaphobic committed
259

260 261
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
262
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
263

264 265 266
    if (waitingParamCount == 0) {
        // Now that we know vehicle is up to date persist
        _saveToEEPROM();
267
        _writeLocalParamCache(uasId, componentId);
268
    }
dogmaphobic's avatar
dogmaphobic committed
269

270
    _checkInitialLoadComplete();
271 272 273 274
}

/// Connected to Fact::valueUpdated
///
275
/// Writes the parameter to mavlink, sets up for write wait
276 277 278 279
void ParameterLoader::_valueUpdated(const QVariant& value)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
280

281
    int componentId = fact->componentId();
282
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
283

284
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
285

286
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
287 288
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
289
    _waitingParamTimeoutTimer.start();
290
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
291

292
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
293

294 295
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
296

297 298
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
299
    }
300 301
}

dogmaphobic's avatar
dogmaphobic committed
302
void ParameterLoader::refreshAllParameters(uint8_t componentID)
303
{
304
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
305

306 307 308 309
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

310
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
311
    foreach (int cid, _paramCountMap.keys()) {
312
        // Add/Update all indices to the wait list, parameter index is 0-based
dogmaphobic's avatar
dogmaphobic committed
313 314 315
        if(componentID != MAV_COMP_ID_ALL && componentID != cid)
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
316
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
317
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
318 319
        }
    }
dogmaphobic's avatar
dogmaphobic committed
320

321
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
322

323
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
324
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
325

326
    mavlink_message_t msg;
dogmaphobic's avatar
dogmaphobic committed
327
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), componentID);
328
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
dogmaphobic's avatar
dogmaphobic committed
329

dogmaphobic's avatar
dogmaphobic committed
330 331
    QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID);
    qCDebug(ParameterLoaderLog) << "Request to refresh all parameters for component ID:" << what;
332 333 334 335 336 337 338 339
}

void ParameterLoader::_determineDefaultComponentId(void)
{
    if (_defaultComponentId == FactSystem::defaultComponentId) {
        // We don't have a default component id yet. That means the plugin can't provide
        // the param to trigger off of. Instead we use the most prominent component id in
        // the set of parameters. Better than nothing!
dogmaphobic's avatar
dogmaphobic committed
340

341
        _defaultComponentId = -1;
342
        int largestCompParamCount = 0;
343
        foreach(int componentId, _mapParameterName2Variant.keys()) {
344 345 346
            int compParamCount = _mapParameterName2Variant[componentId].count();
            if (compParamCount > largestCompParamCount) {
                largestCompParamCount = compParamCount;
347 348 349
                _defaultComponentId = componentId;
            }
        }
350 351 352 353

        if (_defaultComponentId == -1) {
            qWarning() << "All parameters missing, unable to determine default componet id";
        }
354 355 356 357 358 359 360 361
    }
}

/// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterLoader::_actualComponentId(int componentId)
{
    if (componentId == FactSystem::defaultComponentId) {
        componentId = _defaultComponentId;
Don Gagne's avatar
Don Gagne committed
362
        if (componentId == FactSystem::defaultComponentId) {
Don Gagne's avatar
Don Gagne committed
363 364
            qWarning() << "Default component id not set";
        }
365
    }
dogmaphobic's avatar
dogmaphobic committed
366

367 368 369 370 371
    return componentId;
}

void ParameterLoader::refreshParameter(int componentId, const QString& name)
{
372 373
    componentId = _actualComponentId(componentId);
    qCDebug(ParameterLoaderLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
374

375 376 377
    _dataMutex.lock();

    Q_ASSERT(_waitingReadParamNameMap.contains(componentId));
dogmaphobic's avatar
dogmaphobic committed
378

379
    if (_waitingReadParamNameMap.contains(componentId)) {
380 381
        _waitingReadParamNameMap[componentId].remove(name); // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][name] = 0;    // Add new wait entry and update retry count
382 383
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
384

385 386 387
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
388 389 390 391 392
}

void ParameterLoader::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
    componentId = _actualComponentId(componentId);
393 394
    qCDebug(ParameterLoaderLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";

395
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
396 397 398 399 400 401
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

402
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
403
{
404
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
405

406 407
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
408
        ret = _mapParameterName2Variant[componentId].contains(name);
409
    }
410 411

    return ret;
412 413 414 415 416
}

Fact* ParameterLoader::getFact(int componentId, const QString& name)
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
417

418
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) {
Don Gagne's avatar
Don Gagne committed
419 420
        qgcApp()->reportMissingParameter(componentId, name);
        return &_defaultFact;
421
    }
dogmaphobic's avatar
dogmaphobic committed
422

Don Gagne's avatar
Don Gagne committed
423
    return _mapParameterName2Variant[componentId][name].value<Fact*>();
424
}
425

Don Gagne's avatar
Don Gagne committed
426
QStringList ParameterLoader::parameterNames(int componentId)
427
{
dogmaphobic's avatar
dogmaphobic committed
428 429
    QStringList names;

430
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
431 432 433 434
        names << paramName;
    }

    return names;
435 436 437 438 439
}

void ParameterLoader::_setupGroupMap(void)
{
    foreach (int componentId, _mapParameterName2Variant.keys()) {
440
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
441 442 443 444 445 446 447 448 449 450
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
451 452 453 454 455 456

void ParameterLoader::_waitingParamTimeout(void)
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
dogmaphobic's avatar
dogmaphobic committed
457

458
    // We timed out waiting for some parameters from the initial set. Re-request those.
dogmaphobic's avatar
dogmaphobic committed
459

460 461
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
462 463 464 465 466 467 468 469 470 471 472 473
        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
            if (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetry) {
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
                qCDebug(ParameterLoaderLog) << "Giving up on (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
                paramsRequested = true;
                _readParameterRaw(componentId, "", paramIndex);
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
dogmaphobic's avatar
dogmaphobic committed
474

475 476 477
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
478 479 480
            }
        }
    }
481 482
    // We need to check for initial load complete here as well, since it could complete on a max retry failure
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
483

484 485
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
486
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
487
                paramsRequested = true;
488
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
489
                _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
490
                qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
491

492 493 494 495 496 497
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
498

499 500
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
501
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
502
                paramsRequested = true;
503
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
504
                _readParameterRaw(componentId, paramName, -1);
505
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
506

507 508 509 510 511 512
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
513

514 515 516 517 518 519 520 521 522 523 524 525 526 527 528
Out:
    if (paramsRequested) {
        _waitingParamTimeoutTimer.start();
    }
}

void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
    mavlink_msg_param_request_read_pack(_mavlink->getSystemId(),    // Our system id
                                        _mavlink->getComponentId(), // Our component id
                                        &msg,                       // Pack into this mavlink_message_t
529
                                        _vehicle->id(),             // Target system id
530 531 532
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
533
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
534 535 536 537 538 539
}

void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
540

541
    FactMetaData::ValueType_t factType = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
542
    p.param_type = _factTypeToMavType(factType);
dogmaphobic's avatar
dogmaphobic committed
543

544 545
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
546
            union_value.param_uint8 = (uint8_t)value.toUInt();
547
            break;
dogmaphobic's avatar
dogmaphobic committed
548

549
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
550
            union_value.param_int8 = (int8_t)value.toInt();
551
            break;
dogmaphobic's avatar
dogmaphobic committed
552

553
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
554
            union_value.param_uint16 = (uint16_t)value.toUInt();
555
            break;
dogmaphobic's avatar
dogmaphobic committed
556

557
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
558
            union_value.param_int16 = (int16_t)value.toInt();
559
            break;
dogmaphobic's avatar
dogmaphobic committed
560

561
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
562
            union_value.param_uint32 = (uint32_t)value.toUInt();
563
            break;
dogmaphobic's avatar
dogmaphobic committed
564

565 566 567
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
568

569 570 571
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
572

573
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
574
            union_value.param_int32 = (int32_t)value.toInt();
575 576
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
577

578
    p.param_value = union_value.param_float;
579
    p.target_system = (uint8_t)_vehicle->id();
580
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
581

582
    strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id));
dogmaphobic's avatar
dogmaphobic committed
583

584 585
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
586
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
587 588
}

589
void ParameterLoader::_writeLocalParamCache(int uasId, int componentId)
590
{
591
    MapID2NamedParam cache_map;
592

593 594 595 596
    foreach(int id, _mapParameterId2Name[componentId].keys()) {
        const QString name(_mapParameterId2Name[componentId][id]);
        const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
        cache_map[id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue()));
597 598
    }

599
    QFile cache_file(parameterCacheFile(uasId, componentId));
600 601 602 603 604 605
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

    QDataStream ds(&cache_file);
    ds << cache_map;
}

606 607 608 609 610 611 612
QDir ParameterLoader::parameterCacheDir()
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

QString ParameterLoader::parameterCacheFile(int uasId, int componentId)
613
{
614
    return parameterCacheDir().filePath(QString("%1_%2").arg(uasId).arg(componentId));
615 616
}

617
void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value)
618 619 620
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
621 622
    MapID2NamedParam cache_map;
    QFile cache_file(parameterCacheFile(uasId, componentId));
623
    if (!cache_file.exists()) {
624
        /* no local cache, just wait for them to come in*/
625 626 627 628 629 630 631 632 633
        return;
    }
    cache_file.open(QIODevice::ReadOnly);

    /* Deserialize the parameter cache table */
    QDataStream ds(&cache_file);
    ds >> cache_map;

    /* compute the crc of the local cache to check against the remote */
634 635 636 637 638 639 640

    foreach(int id, cache_map.keys()) {
        const QString name(cache_map[id].first);
        const void *vdat = cache_map[id].second.second.constData();
        const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first);
        crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(),  crc32_value);
        crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value);
641 642 643
    }

    if (crc32_value == hash_value.toUInt()) {
644
        qCInfo(ParameterLoaderLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
645
        /* if the two param set hashes match, just load from the disk */
646 647 648 649 650 651 652
        int count = cache_map.count();
        foreach(int id, cache_map.keys()) {
            const QString &name = cache_map[id].first;
            const QVariant &value = cache_map[id].second.second;
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first);
            const int mavType = _factTypeToMavType(fact_type);
            _parameterUpdate(uasId, componentId, name, count, id, mavType, value);
653
        }
654 655 656 657 658 659 660 661 662 663 664 665
        // Return the hash value to notify we don't want any more updates
        mavlink_param_set_t     p;
        mavlink_param_union_t   union_value;
        p.param_type = MAV_PARAM_TYPE_UINT32;
        strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id));
        union_value.param_uint32 = crc32_value;
        p.param_value = union_value.param_float;
        p.target_system = (uint8_t)_vehicle->id();
        p.target_component = (uint8_t)componentId;
        mavlink_message_t msg;
        mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
666 667 668
    }
}

669 670
void ParameterLoader::_saveToEEPROM(void)
{
671 672 673 674 675
    if (_saveRequired) {
        _saveRequired = false;
        if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) {
            mavlink_message_t msg;
            mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
676
            _vehicle->sendMessageOnLink(_dedicatedLink, msg);
677 678 679 680
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
        } else {
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
        }
Don Gagne's avatar
Don Gagne committed
681
    }
682 683
}

684
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
685
{
686
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
687

688 689 690 691 692 693
    while (!stream.atEnd()) {
        QString line = stream.readLine();
        if (!line.startsWith("#")) {
            QStringList wpParams = line.split("\t");
            int lineMavId = wpParams.at(0).toInt();
            if (wpParams.size() == 5) {
Don Gagne's avatar
Don Gagne committed
694 695
                if (_vehicle->id() != lineMavId) {
                    return QString("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.").arg(lineMavId).arg(_vehicle->id());
dogmaphobic's avatar
dogmaphobic committed
696 697
                }

698 699 700 701
                int     componentId = wpParams.at(1).toInt();
                QString paramName = wpParams.at(2);
                QString valStr = wpParams.at(3);
                uint    mavType = wpParams.at(4).toUInt();
dogmaphobic's avatar
dogmaphobic committed
702

703
                if (!_vehicle->autopilotPlugin()->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
704 705 706 707
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
708 709
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
710

711
                Fact* fact = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName);
712
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
713 714 715 716
                    QString error;
                    error  = QString("Skipped parameter %1:%2 - type mismatch %3:%4\n").arg(componentId).arg(paramName).arg(fact->type()).arg(_mavTypeToFactType((MAV_PARAM_TYPE)mavType));
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
717 718
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
719

720
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
721
                fact->setRawValue(valStr);
722 723 724
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
725

726
    return errors;
727 728
}

729
void ParameterLoader::writeParametersToStream(QTextStream &stream)
730
{
731
    stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
732 733 734 735
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
736
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
737
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
738 739 740 741 742
            if (fact) {
                stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
            } else {
                qWarning() << "Internal error: missing fact";
            }
743 744
        }
    }
dogmaphobic's avatar
dogmaphobic committed
745

746 747 748 749 750 751 752 753
    stream.flush();
}

MAV_PARAM_TYPE ParameterLoader::_factTypeToMavType(FactMetaData::ValueType_t factType)
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
754

755 756
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
757

758 759
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
760

761 762
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
763

764 765
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
766

767 768
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
769

770 771 772
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
773

774 775 776 777 778 779 780 781 782 783
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

FactMetaData::ValueType_t ParameterLoader::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
784

785 786
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
787

788 789
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
790

791 792
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
793

794 795
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
796

797 798
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
799

800 801 802
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
803

804 805 806 807 808 809 810 811 812
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

void ParameterLoader::_restartWaitingParamTimer(void)
{
    _waitingParamTimeoutTimer.start();
}
813

814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840
/// Adds meta data to all params after initial load completes
void ParameterLoader::_addMetaDataToAll(void)
{
     if (_defaultComponentId == FactSystem::defaultComponentId) {
         // We don't know what the default component is so we can't support meta data
         return;
     }

     if (_parameterMetaData) {
         // This should only be called once
         qWarning() << "Internal Error: ParameterLoader::_addMetaDataToAll with _parameterMetaData non NULL";
         return;
     }

    // Load best parameter meta data set
     int majorVersion, minorVersion;
     QString metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
     _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
     qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;

    // Loop over all parameters in default component adding meta data
    QVariantMap& factMap = _mapParameterName2Variant[_defaultComponentId];
    foreach (const QString& key, factMap.keys()) {
        _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value<Fact*>(), _vehicle->vehicleType());
    }
}

841 842 843 844 845 846
void ParameterLoader::_checkInitialLoadComplete(void)
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
847

848 849 850 851 852 853
    foreach (int componentId, _waitingReadParamIndexMap.keys()) {
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
854

855 856
    // We aren't waiting for any more initial parameter updates, initial parameter loading is complete
    _initialLoadComplete = true;
dogmaphobic's avatar
dogmaphobic committed
857

858 859 860 861 862 863 864 865 866 867 868 869 870
    // Check for load failures
    QString indexList;
    bool initialLoadFailures = false;
    foreach (int componentId, _failedReadParamIndexMap.keys()) {
        foreach (int paramIndex, _failedReadParamIndexMap[componentId]) {
            if (initialLoadFailures) {
                indexList += ", ";
            }
            indexList += QString("%1").arg(paramIndex);
            initialLoadFailures = true;
            qCDebug(ParameterLoaderLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
        }
    }
dogmaphobic's avatar
dogmaphobic committed
871

872
    // Check for any errors during vehicle boot
dogmaphobic's avatar
dogmaphobic committed
873

874
    UASMessageHandler* msgHandler = qgcApp()->toolbox()->uasMessageHandler();
875
    if (msgHandler->getErrorCountTotal()) {
876
        QString errors;
877
        bool firstError = true;
878
        bool errorsFound = false;
dogmaphobic's avatar
dogmaphobic committed
879

880 881 882
        msgHandler->lockAccess();
        foreach (UASMessage* msg, msgHandler->messages()) {
            if (msg->severityIsError()) {
883
                if (!firstError) {
dogmaphobic's avatar
dogmaphobic committed
884
                    errors += "<br>";
885 886
                }
                errors += " - ";
887
                errors += msg->getText();
888
                firstError = false;
889
                errorsFound = true;
890 891
            }
        }
892
        msgHandler->showErrorsInToolbar();
893
        msgHandler->unlockAccess();
dogmaphobic's avatar
dogmaphobic committed
894

895
        if (errorsFound) {
dogmaphobic's avatar
dogmaphobic committed
896
            QString errorMsg = QString("<b>Critical safety issue detected:</b><br>%1").arg(errors);
897
            qgcApp()->showMessage(errorMsg);
898
        }
899
    }
dogmaphobic's avatar
dogmaphobic committed
900

901 902 903
    // We can now add meta data since we should know parameter set version
    _addMetaDataToAll();

904
    // Warn of parameter load failure
dogmaphobic's avatar
dogmaphobic committed
905

906
    if (initialLoadFailures) {
907
        qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
dogmaphobic's avatar
dogmaphobic committed
908
                              "This will cause QGroundControl to be unable to display its full user interface. "
909 910
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
                              "If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
911
        qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
912
        emit parametersReady(true);
913 914 915 916 917
    } else {
        // No failed parameters, ok to signal ready
        _parametersReady = true;
        _determineDefaultComponentId();
        _setupGroupMap();
918
        emit parametersReady(false);
919
    }
920
}
921 922 923 924 925 926 927

void ParameterLoader::_initialRequestTimeout(void)
{
    qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying");
    refreshAllParameters();
    _initialRequestTimeoutTimer.start();
}
928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065

QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
{
    bool            cacheHit = false;
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    // Cached files are stored in settings location
    QSettings settings;
    QDir cacheDir = QFileInfo(settings.fileName()).dir();

    // First look for a direct cache hit
    int cacheMinorVersion, cacheMajorVersion;
    QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion)));
    if (cacheFile.exists()) {
        plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion);
        if (wantedMajorVersion != cacheMajorVersion) {
            qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
        } else {
            qCDebug(ParameterLoaderLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
            cacheHit = true;
        }
    }

    if (!cacheHit) {
        // No direct hit, look for lower param set version
        QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType);
        QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name);

        // Find the highest major version number which is below the vehicles major version number
        int cacheHitIndex = -1;
        cacheMajorVersion = -1;
        QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType));
        for (int i=0; i< cacheHits.count(); i++) {
            if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) {
                int majorVersion = regExp.capturedTexts()[0].toInt();
                if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) {
                    cacheMajorVersion = majorVersion;
                    cacheHitIndex = i;
                }
            }
        }

        if (cacheHitIndex != -1) {
            // We have a cache hit on a lower major version, read minor version as well
            int majorVersion;
            cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex]));
            plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion);
            if (majorVersion != cacheMajorVersion) {
                qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
                cacheHit = false;
            } else {
                qCDebug(ParameterLoaderLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile();
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
    qCDebug(ParameterLoaderLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
    if (cacheHit) {
        // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
        if (internalMajorVersion == wantedMajorVersion) {
            if (cacheMajorVersion == wantedMajorVersion) {
                // Both internal and cache are direct hit on major version, Use higher minor version number
                cacheHit = cacheMinorVersion > internalMinorVersion;
            } else {
                // Direct internal hit, but not direct hit in cache, use internal
                cacheHit = false;
            }
        } else {
            if (cacheMajorVersion == wantedMajorVersion) {
                // Direct hit on cache, no direct hit on internal, use cache
                cacheHit = true;
            } else {
                // No direct hit anywhere, use internal
                cacheHit = false;
            }
        }
    }

    QString metaDataFile;
    if (cacheHit && !qgcApp()->runningUnitTests()) {
        majorVersion = cacheMajorVersion;
        minorVersion = cacheMinorVersion;
        metaDataFile = cacheFile.fileName();
    } else {
        majorVersion = internalMajorVersion;
        minorVersion = internalMinorVersion;
        metaDataFile = internalMetaDataFile;
    }
    qCDebug(ParameterLoaderLog) << "ParameterLoader::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;

    return metaDataFile;
}

void ParameterLoader::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
    qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
    QString cacheHit = ParameterLoader::parameterMetaDataFile(firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
    qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;

    bool cacheNewFile = false;
    if (cacheHit.isEmpty()) {
        // No cache hits, store the new file
        cacheNewFile = true;
    } else if (cacheMajorVersion == newMajorVersion) {
        // Direct hit on major version in cache:
        //      Cache new file if newer minor version
        //      Also delete older cache file
        if (newMinorVersion > cacheMinorVersion) {
            cacheNewFile = true;
            QFile::remove(cacheHit);
        }
    } else {
        // Indirect hit in cache, store new file
        cacheNewFile = true;
    }

    if (cacheNewFile) {
        // Cached files are stored in settings location. Copy from current file to cache naming.

        QSettings settings;
        QDir cacheDir = QFileInfo(settings.fileName()).dir();
        QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(newMajorVersion)));
        qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile caching file:" << cacheFile.fileName();
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}