ParameterLoader.cc 45.4 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
    , _waitingForDefaultComponent(false)
57
    , _saveRequired(false)
58
    , _defaultComponentId(FactSystem::defaultComponentId)
59 60
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
61
    , _totalParamCount(0)
62
{
63
    Q_ASSERT(_vehicle);
64
    Q_ASSERT(_mavlink);
dogmaphobic's avatar
dogmaphobic committed
65

66 67
    // 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
68

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

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

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

79 80
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();
    _defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
81
    qCDebug(ParameterLoaderLog) << "Default component param" << _defaultComponentIdParam;
82

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

ParameterLoader::~ParameterLoader()
{
90
    delete _parameterMetaData;
91 92 93
}

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

101 102
    _initialRequestTimeoutTimer.stop();

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

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

121 122 123 124 125 126 127
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

128 129
    if (parameterName == "_HASH_CHECK") {
        /* we received a cache hash, potentially load from cache */
130
        _tryCacheHashLoad(uasId, componentId, value);
131 132
        return;
    }
133
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
134

135 136 137 138 139
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
140 141

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

143 144
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
145 146 147 148
        // 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;
149
        }
dogmaphobic's avatar
dogmaphobic committed
150

151 152 153
        // 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
154

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

158 159 160 161 162 163 164 165 166 167 168 169
    // Determine default component id
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        qCDebug(ParameterLoaderLog) << "Default component id determined" << componentId;
        _defaultComponentId = componentId;
    }

    bool componentParamsComplete = false;
    if (_waitingReadParamIndexMap[componentId].count() == 1) {
        // We need to know when we get the last param from a component in order to complete setup
        componentParamsComplete = true;
    }

170 171 172 173 174 175 176 177
    if (_waitingReadParamIndexMap[componentId].contains(parameterId) ||
        _waitingReadParamNameMap[componentId].contains(parameterName) ||
        _waitingWriteParamNameMap[componentId].contains(parameterName)) {
        // We were waiting for this parameter, restart wait timer. Otherwise it is a spurious parameter update which
        // means we should not reset the wait timer.
        _waitingParamTimeoutTimer.start();
    }

178
    // Remove this parameter from the waiting lists
179 180 181
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
182
    qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
183 184 185 186
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

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

188 189 190
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
191

192 193 194 195 196 197 198
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

dogmaphobic's avatar
dogmaphobic committed
199

200 201 202 203 204 205
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
206

207 208 209 210 211 212
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
213

214 215 216
    int waitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount + waitingWriteParamNameCount;
    if (waitingParamCount) {
        qCDebug(ParameterLoaderLog) << "waitingParamCount:" << waitingParamCount;
217 218 219
    } else if (_defaultComponentId != FactSystem::defaultComponentId) {
        // No more parameters to wait for, stop the timeout. Be careful to not stop timer if we don't have the default
        // component yet.
220 221 222 223 224 225 226 227 228
        _waitingParamTimeoutTimer.stop();
    }

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

230 231 232 233 234
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

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

238 239 240 241 242 243
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
244
                factType = FactMetaData::valueTypeInt8;
245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268
                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
269

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

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

274
        // 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
275
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated);
276
    }
dogmaphobic's avatar
dogmaphobic committed
277

Don Gagne's avatar
Don Gagne committed
278 279
    _dataMutex.unlock();

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

282 283
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
284
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
285

286 287 288 289 290 291 292 293 294 295 296 297 298
    if (componentParamsComplete) {
        if (componentId == _defaultComponentId) {
            // Add meta data to default component. We need to do this before we setup the group map since group
            // map requires meta data.
            _addMetaDataToDefaultComponent();
        }

        // When we are getting the very last component param index, reset the group maps to update for the
        // new params. By handling this here, we can pick up components which finish up later than the default
        // component param set.
        _setupGroupMap();
    }

299 300 301
    if (waitingParamCount == 0) {
        // Now that we know vehicle is up to date persist
        _saveToEEPROM();
302
        _writeLocalParamCache(uasId, componentId);
303
    }
dogmaphobic's avatar
dogmaphobic committed
304

305 306
    // Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check.
    _checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
307 308 309 310
}

/// Connected to Fact::valueUpdated
///
311
/// Writes the parameter to mavlink, sets up for write wait
312 313 314 315
void ParameterLoader::_valueUpdated(const QVariant& value)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
316

317
    int componentId = fact->componentId();
318
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
319

320
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
321

322
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
323 324
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
325
    _waitingParamTimeoutTimer.start();
326
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
327

328
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
329

330 331
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
332

333 334
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
335
    }
336 337
}

dogmaphobic's avatar
dogmaphobic committed
338
void ParameterLoader::refreshAllParameters(uint8_t componentID)
339
{
340
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
341

342 343 344 345
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

346
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
347
    foreach (int cid, _paramCountMap.keys()) {
348
        // Add/Update all indices to the wait list, parameter index is 0-based
dogmaphobic's avatar
dogmaphobic committed
349 350 351
        if(componentID != MAV_COMP_ID_ALL && componentID != cid)
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
352
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
353
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
354 355
        }
    }
dogmaphobic's avatar
dogmaphobic committed
356

357
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
358

359
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
360
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
361

362
    mavlink_message_t msg;
dogmaphobic's avatar
dogmaphobic committed
363
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), componentID);
364
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
dogmaphobic's avatar
dogmaphobic committed
365

dogmaphobic's avatar
dogmaphobic committed
366 367
    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;
368 369 370 371 372 373 374 375
}

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
376

377
        _defaultComponentId = -1;
378
        int largestCompParamCount = 0;
379
        foreach(int componentId, _mapParameterName2Variant.keys()) {
380 381 382
            int compParamCount = _mapParameterName2Variant[componentId].count();
            if (compParamCount > largestCompParamCount) {
                largestCompParamCount = compParamCount;
383 384 385
                _defaultComponentId = componentId;
            }
        }
386 387 388 389

        if (_defaultComponentId == -1) {
            qWarning() << "All parameters missing, unable to determine default componet id";
        }
390 391 392 393 394 395 396 397
    }
}

/// 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
398
        if (componentId == FactSystem::defaultComponentId) {
Don Gagne's avatar
Don Gagne committed
399 400
            qWarning() << "Default component id not set";
        }
401
    }
dogmaphobic's avatar
dogmaphobic committed
402

403 404 405 406 407
    return componentId;
}

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

411 412 413
    _dataMutex.lock();

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

415
    if (_waitingReadParamNameMap.contains(componentId)) {
416 417
        _waitingReadParamNameMap[componentId].remove(name); // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][name] = 0;    // Add new wait entry and update retry count
418 419
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
420

421 422 423
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
424 425 426 427 428
}

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

431
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
432 433 434 435 436 437
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

438
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
439
{
440
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
441

442 443
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
444
        ret = _mapParameterName2Variant[componentId].contains(name);
445
    }
446 447

    return ret;
448 449 450 451 452
}

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

454
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) {
Don Gagne's avatar
Don Gagne committed
455 456
        qgcApp()->reportMissingParameter(componentId, name);
        return &_defaultFact;
457
    }
dogmaphobic's avatar
dogmaphobic committed
458

Don Gagne's avatar
Don Gagne committed
459
    return _mapParameterName2Variant[componentId][name].value<Fact*>();
460
}
461

Don Gagne's avatar
Don Gagne committed
462
QStringList ParameterLoader::parameterNames(int componentId)
463
{
dogmaphobic's avatar
dogmaphobic committed
464 465
    QStringList names;

466
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
467 468 469 470
        names << paramName;
    }

    return names;
471 472 473 474
}

void ParameterLoader::_setupGroupMap(void)
{
475 476 477
    // Must be able to handle being called multiple times
    _mapGroup2ParameterName.clear();

478
    foreach (int componentId, _mapParameterName2Variant.keys()) {
479
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
480 481 482 483 484 485 486 487 488 489
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
490 491 492 493 494 495

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

497
    // First check for any missing parameters from the initial index based load
498 499
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
500 501 502 503 504 505 506 507 508 509 510 511
        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
512

513 514 515
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
516 517 518
            }
        }
    }
519 520 521 522 523 524 525 526 527 528 529 530

    if (!paramsRequested && _defaultComponentId == FactSystem::defaultComponentId && !_waitingForDefaultComponent) {
        // Initial load is complete but we still don't have default component params. Wait one more cycle to see if the
        // default component finally shows up.
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

    // Check for initial load complete success/failure. Fail load if we don't have a default component at this point.
    _checkInitialLoadComplete(true /* failIfNoDefaultComponent */);
dogmaphobic's avatar
dogmaphobic committed
531

532 533
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
534
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
535
                paramsRequested = true;
536
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
537
                _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
538
                qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
539

540 541 542 543 544 545
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
546

547 548
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
549
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
550
                paramsRequested = true;
551
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
552
                _readParameterRaw(componentId, paramName, -1);
553
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
554

555 556 557 558 559 560
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
561

562 563 564 565 566 567 568 569 570 571 572 573 574 575 576
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
577
                                        _vehicle->id(),             // Target system id
578 579 580
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
581
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
582 583 584 585 586 587
}

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
588

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

592 593
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
594
            union_value.param_uint8 = (uint8_t)value.toUInt();
595
            break;
dogmaphobic's avatar
dogmaphobic committed
596

597
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
598
            union_value.param_int8 = (int8_t)value.toInt();
599
            break;
dogmaphobic's avatar
dogmaphobic committed
600

601
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
602
            union_value.param_uint16 = (uint16_t)value.toUInt();
603
            break;
dogmaphobic's avatar
dogmaphobic committed
604

605
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
606
            union_value.param_int16 = (int16_t)value.toInt();
607
            break;
dogmaphobic's avatar
dogmaphobic committed
608

609
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
610
            union_value.param_uint32 = (uint32_t)value.toUInt();
611
            break;
dogmaphobic's avatar
dogmaphobic committed
612

613 614 615
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
616

617 618 619
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
620

621
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
622
            union_value.param_int32 = (int32_t)value.toInt();
623 624
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
625

626
    p.param_value = union_value.param_float;
627
    p.target_system = (uint8_t)_vehicle->id();
628
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
629

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

632 633
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
634
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
635 636
}

637
void ParameterLoader::_writeLocalParamCache(int uasId, int componentId)
638
{
639
    MapID2NamedParam cache_map;
640

641 642 643 644
    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()));
645 646
    }

647
    QFile cache_file(parameterCacheFile(uasId, componentId));
648 649 650 651 652 653
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

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

654 655 656 657 658 659 660
QDir ParameterLoader::parameterCacheDir()
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

QString ParameterLoader::parameterCacheFile(int uasId, int componentId)
661
{
662
    return parameterCacheDir().filePath(QString("%1_%2").arg(uasId).arg(componentId));
663 664
}

665
void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value)
666 667 668
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
669 670
    MapID2NamedParam cache_map;
    QFile cache_file(parameterCacheFile(uasId, componentId));
671
    if (!cache_file.exists()) {
672
        /* no local cache, just wait for them to come in*/
673 674 675 676 677 678 679 680 681
        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 */
682 683 684 685 686 687 688

    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);
689 690 691
    }

    if (crc32_value == hash_value.toUInt()) {
692
        qCInfo(ParameterLoaderLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
693
        /* if the two param set hashes match, just load from the disk */
694 695 696 697 698 699 700
        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);
701
        }
702 703 704 705 706 707 708 709 710 711 712 713
        // 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);
714 715 716
    }
}

717 718
void ParameterLoader::_saveToEEPROM(void)
{
719 720 721 722 723
    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);
724
            _vehicle->sendMessageOnLink(_dedicatedLink, msg);
725 726 727 728
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
        } else {
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
        }
Don Gagne's avatar
Don Gagne committed
729
    }
730 731
}

732
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
733
{
734
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
735

736 737 738 739 740 741
    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
742 743
                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
744 745
                }

746 747 748 749
                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
750

751
                if (!_vehicle->autopilotPlugin()->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
752 753 754 755
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
756 757
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
758

759
                Fact* fact = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName);
760
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
761 762 763 764
                    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;
765 766
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
767

768
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
769
                fact->setRawValue(valStr);
770 771 772
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
773

774
    return errors;
775 776
}

777
void ParameterLoader::writeParametersToStream(QTextStream &stream)
778
{
779
    stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
780 781 782 783
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
784
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
785
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
786 787 788 789 790
            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";
            }
791 792
        }
    }
dogmaphobic's avatar
dogmaphobic committed
793

794 795 796 797 798 799 800 801
    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
802

803 804
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
805

806 807
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
808

809 810
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
811

812 813
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
814

815 816
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
817

818 819 820
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
821

822 823 824 825 826 827 828 829 830 831
        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
832

833 834
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
835

836 837
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
838

839 840
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
841

842 843
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
844

845 846
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
847

848 849 850
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
851

852 853 854 855 856 857 858 859 860
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

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

862
void ParameterLoader::_addMetaDataToDefaultComponent(void)
863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887
{
     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());
    }
}

888 889
/// @param failIfNoDefaultComponent true: Fails parameter load if no default component but we should have one
void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
890 891 892 893 894
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
895

896 897 898 899 900 901
    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
902

903 904 905 906 907
    if (!failIfNoDefaultComponent && _defaultComponentId == FactSystem::defaultComponentId) {
        // We are still waiting for default component to show up
        return;
    }

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

911
    // Check for any errors during vehicle boot
dogmaphobic's avatar
dogmaphobic committed
912

913
    UASMessageHandler* msgHandler = qgcApp()->toolbox()->uasMessageHandler();
914
    if (msgHandler->getErrorCountTotal()) {
915
        QString errors;
916
        bool firstError = true;
917
        bool errorsFound = false;
dogmaphobic's avatar
dogmaphobic committed
918

919 920 921
        msgHandler->lockAccess();
        foreach (UASMessage* msg, msgHandler->messages()) {
            if (msg->severityIsError()) {
922
                if (!firstError) {
dogmaphobic's avatar
dogmaphobic committed
923
                    errors += "<br>";
924 925
                }
                errors += " - ";
926
                errors += msg->getText();
927
                firstError = false;
928
                errorsFound = true;
929 930
            }
        }
931
        msgHandler->showErrorsInToolbar();
932
        msgHandler->unlockAccess();
dogmaphobic's avatar
dogmaphobic committed
933

934
        if (errorsFound) {
dogmaphobic's avatar
dogmaphobic committed
935
            QString errorMsg = QString("<b>Critical safety issue detected:</b><br>%1").arg(errors);
936
            qgcApp()->showMessage(errorMsg);
937
        }
938
    }
dogmaphobic's avatar
dogmaphobic committed
939

940 941 942 943 944 945 946 947 948 949 950 951 952
    // Check for index based 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 << ")";
        }
    }
953
    if (initialLoadFailures) {
954
        qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
dogmaphobic's avatar
dogmaphobic committed
955
                              "This will cause QGroundControl to be unable to display its full user interface. "
956 957
                              "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.");
958
        qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
959
        emit parametersReady(true);
960
        return;
961
    }
962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977

    // Check for missing default component when we should have one
    if (_defaultComponentId == FactSystem::defaultComponentId && !_defaultComponentIdParam.isEmpty()) {
        qgcApp()->showMessage("QGroundControl did not receive parameters from the default component. "
                              "This will cause QGroundControl to be unable to display its full user interface. "
                              "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.");
        qCWarning(ParameterLoaderLog) << "Default component was never found, param:" << _defaultComponentIdParam;
        emit parametersReady(true);
        return;
    }

    // No failures, signal good load
    _parametersReady = true;
    _determineDefaultComponentId();
    emit parametersReady(false);
978
}
979 980 981 982 983 984 985

void ParameterLoader::_initialRequestTimeout(void)
{
    qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying");
    refreshAllParameters();
    _initialRequestTimeoutTimer.start();
}
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 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123

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