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

10 11 12 13

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

14
#include "ParameterManager.h"
15 16
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
17
#include "QGCApplication.h"
18
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
19
#include "FirmwarePlugin.h"
20
#include "UAS.h"
21
#include "JsonHelper.h"
22

23
#include <QEasingCurve>
24 25
#include <QFile>
#include <QDebug>
26
#include <QVariantAnimation>
27
#include <QJsonArray>
28

29 30 31 32 33
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;

34 35
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
36

37
Fact ParameterManager::_defaultFact;
Don Gagne's avatar
Don Gagne committed
38

39 40 41 42 43
const char* ParameterManager::_cachedMetaDataFilePrefix =   "ParameterFactMetaData";
const char* ParameterManager::_jsonParametersKey =          "parameters";
const char* ParameterManager::_jsonCompIdKey =              "compId";
const char* ParameterManager::_jsonParamNameKey =           "name";
const char* ParameterManager::_jsonParamValueKey =          "value";
44

45
ParameterManager::ParameterManager(Vehicle* vehicle)
46
    : QObject(vehicle)
47
    , _vehicle(vehicle)
48
    , _mavlink(NULL)
49
    , _loadProgress(0.0)
50
    , _parametersReady(false)
51
    , _missingParameters(false)
52
    , _initialLoadComplete(false)
53
    , _waitingForDefaultComponent(false)
54
    , _saveRequired(false)
55 56
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
Don Gagne's avatar
Don Gagne committed
57 58 59
    , _prevWaitingReadParamIndexCount(0)
    , _prevWaitingReadParamNameCount(0)
    , _prevWaitingWriteParamNameCount(0)
60
    , _initialRequestRetryCount(0)
61
    , _disableAllRetries(false)
62
    , _totalParamCount(0)
63
{
64 65
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

66 67 68 69 70 71
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

    _mavlink = qgcApp()->toolbox()->mavlinkProtocol();
dogmaphobic's avatar
dogmaphobic committed
72

73
    _initialRequestTimeoutTimer.setSingleShot(true);
74
    _initialRequestTimeoutTimer.setInterval(5000);
75
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
76

77
    _waitingParamTimeoutTimer.setSingleShot(true);
78
    _waitingParamTimeoutTimer.setInterval(3000);
79
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
80

81
    connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate);
82

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

88
ParameterManager::~ParameterManager()
89
{
90
    delete _parameterMetaData;
91 92 93
}

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

101 102 103 104 105 106 107 108
    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
                                            "_parameterUpdate" <<
                                            "name:" << parameterName <<
                                            "count:" << parameterCount <<
                                            "index:" << parameterId <<
                                            "mavType:" << mavType <<
                                            "value:" << value <<
                                            ")";
109

110
    _initialRequestTimeoutTimer.stop();
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
        qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
117 118 119
        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

Don Gagne's avatar
Don Gagne committed
128
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
129
        /* we received a cache hash, potentially load from cache */
130
        _tryCacheHashLoad(vehicleId, componentId, value);
131 132
        return;
    }
133 134

    _initialRequestTimeoutTimer.stop();
135
    _waitingParamTimeoutTimer.stop();
136

137
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
138

139 140 141 142 143
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
144 145

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

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

155 156 157
        // 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
158

159
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Seeing component for first time - paramcount:" << parameterCount;
160
    }
dogmaphobic's avatar
dogmaphobic committed
161

162 163 164 165 166 167
    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;
    }

168 169 170
    if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
        !_waitingReadParamNameMap[componentId].contains(parameterName) &&
        !_waitingWriteParamNameMap[componentId].contains(parameterName)) {
171
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName;
172 173
    }

174
    // Remove this parameter from the waiting lists
175 176 177
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
178 179 180 181 182 183 184 185 186
    if (_waitingReadParamIndexMap[componentId].count()) {
        qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
    }
    if (_waitingReadParamNameMap[componentId].count()) {
        qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    }
    if (_waitingWriteParamNameMap[componentId].count()) {
        qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
    }
187 188

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

190 191 192
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
193

194 195 196 197
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
198
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
199 200 201 202 203 204
    }

    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
205
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
206
    }
dogmaphobic's avatar
dogmaphobic committed
207

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

Don Gagne's avatar
Don Gagne committed
215 216 217
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
218 219 220 221
        // More params to wait for, restart timer
        _waitingParamTimeoutTimer.start();
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
    } else {
222
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
223 224
    }

Don Gagne's avatar
Don Gagne committed
225 226 227 228 229
    // Update progress bar for waiting reads
    if (readWaitingParamCount == 0) {
        // We are no longer waiting for any reads to complete
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0) {
            // Set progress to 0 if not already there
230
            _setLoadProgress(0.0);
Don Gagne's avatar
Don Gagne committed
231
        }
232
    } else {
233
        _setLoadProgress((double)(_totalParamCount - readWaitingParamCount) / (double)_totalParamCount);
234
    }
dogmaphobic's avatar
dogmaphobic committed
235

236 237 238 239 240
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

241
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
242
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Adding new fact" << parameterName;
dogmaphobic's avatar
dogmaphobic committed
243

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

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

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

280
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
281
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterManager::_valueUpdated);
282
    }
dogmaphobic's avatar
dogmaphobic committed
283

Don Gagne's avatar
Don Gagne committed
284 285
    _dataMutex.unlock();

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

288 289
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
290
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
291

292
    if (componentParamsComplete) {
293
        if (componentId == _vehicle->defaultComponentId()) {
294 295 296 297 298 299 300 301 302 303 304
            // 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();
    }

Don Gagne's avatar
Don Gagne committed
305 306
    if (_prevWaitingWriteParamNameCount != 0 &&  waitingWriteParamNameCount == 0) {
        // If all the writes just finished the vehicle is up to date, so persist.
307 308
        _saveToEEPROM();
    }
dogmaphobic's avatar
dogmaphobic committed
309

Don Gagne's avatar
Don Gagne committed
310 311 312 313 314 315
    // Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
    // which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
    // which in turn causes a perf problem with all the param cache updates.
    if (_vehicle->px4Firmware()) {
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
            // All reads just finished, update the cache
316
            _writeLocalParamCache(vehicleId, componentId);
Don Gagne's avatar
Don Gagne committed
317 318 319 320 321 322 323
        }
    }

    _prevWaitingReadParamIndexCount = waitingReadParamIndexCount;
    _prevWaitingReadParamNameCount = waitingReadParamNameCount;
    _prevWaitingWriteParamNameCount = waitingWriteParamNameCount;

324
    _checkInitialLoadComplete();
325 326

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
327 328 329 330
}

/// Connected to Fact::valueUpdated
///
331
/// Writes the parameter to mavlink, sets up for write wait
332
void ParameterManager::_valueUpdated(const QVariant& value)
333 334 335
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
336

337
    int componentId = fact->componentId();
338
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
339

340
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
341

342
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
343 344
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
345
    _waitingParamTimeoutTimer.start();
346
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
347

348
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
349

350
    _writeParameterRaw(componentId, fact->name(), value);
351
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
352

353 354
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
355
    }
356 357
}

358
void ParameterManager::refreshAllParameters(uint8_t componentId)
359
{
360
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
361

362 363 364 365
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

366
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
367
    foreach (int cid, _paramCountMap.keys()) {
368
        // Add/Update all indices to the wait list, parameter index is 0-based
369
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
370 371
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
372
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
373
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
374 375
        }
    }
dogmaphobic's avatar
dogmaphobic committed
376

377
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
378

379
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
380
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
381

382
    mavlink_message_t msg;
383 384 385 386 387
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,
                                             _vehicle->id(),
388
                                             componentId);
389
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
390

391 392
    QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what;
393 394 395
}

/// Translates FactSystem::defaultComponentId to real component id if needed
396
int ParameterManager::_actualComponentId(int componentId)
397 398
{
    if (componentId == FactSystem::defaultComponentId) {
399
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
400
        if (componentId == FactSystem::defaultComponentId) {
401
            qWarning() << _logVehiclePrefix() << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
402
        }
403
    }
dogmaphobic's avatar
dogmaphobic committed
404

405 406 407
    return componentId;
}

408
void ParameterManager::refreshParameter(int componentId, const QString& name)
409
{
410
    componentId = _actualComponentId(componentId);
411
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
412

413 414 415
    _dataMutex.lock();

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

417
    if (_waitingReadParamNameMap.contains(componentId)) {
418 419 420 421
        QString mappedParamName = _remapParamNameToVersion(name);

        _waitingReadParamNameMap[componentId].remove(mappedParamName);  // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][mappedParamName] = 0;     // Add new wait entry and update retry count
422 423
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
424
    }
dogmaphobic's avatar
dogmaphobic committed
425

426 427 428
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
429 430
}

431
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
432 433
{
    componentId = _actualComponentId(componentId);
434
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
435

436
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
437 438 439 440 441 442
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

443
bool ParameterManager::parameterExists(int componentId, const QString&  name)
444
{
445
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
446

447 448
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
449
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
450
    }
451 452

    return ret;
453 454
}

455
Fact* ParameterManager::getParameter(int componentId, const QString& name)
456 457
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
458

459 460 461
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
462
        return &_defaultFact;
463
    }
dogmaphobic's avatar
dogmaphobic committed
464

465
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
466
}
467

468
QStringList ParameterManager::parameterNames(int componentId)
469
{
dogmaphobic's avatar
dogmaphobic committed
470 471
    QStringList names;

472
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
473 474 475 476
        names << paramName;
    }

    return names;
477 478
}

479
void ParameterManager::_setupGroupMap(void)
480
{
481 482 483
    // Must be able to handle being called multiple times
    _mapGroup2ParameterName.clear();

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

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

497
void ParameterManager::_waitingParamTimeout(void)
498 499 500 501
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
dogmaphobic's avatar
dogmaphobic committed
502

503 504
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout";

505
    // First check for any missing parameters from the initial index based load
506

507 508
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
509 510 511 512 513 514 515 516 517
        if (_waitingReadParamIndexMap[componentId].count()) {
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
        }

        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {            
            if (++batchCount > maxBatchSize) {
                goto Out;
            }

518
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
519
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
520 521
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
522
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
523 524 525 526 527
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
                paramsRequested = true;
                _readParameterRaw(componentId, "", paramIndex);
528
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
529 530 531
            }
        }
    }
532

533 534 535 536
    if (!paramsRequested && !_waitingForDefaultComponent && !_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
        // Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the
        // any show up.
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component params";
537 538 539 540 541 542
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

543
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
544

545 546
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
547
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
548
                paramsRequested = true;
549
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
550
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
551
                    _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
552
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
553 554 555 556 557 558
                    if (++batchCount > maxBatchSize) {
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
559 560 561
                    QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
                    qgcApp()->showMessage(errorMsg);
562 563 564 565
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
566

567 568
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
569
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
570
                paramsRequested = true;
571
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
572 573
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
574
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
575 576 577 578 579 580
                    if (++batchCount > maxBatchSize) {
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
581 582 583
                    QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
                    qgcApp()->showMessage(errorMsg);
584 585 586 587
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
588

589 590
Out:
    if (paramsRequested) {
591
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request";
592 593 594 595
        _waitingParamTimeoutTimer.start();
    }
}

596
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
597 598 599 600 601
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
602 603 604 605 606 607 608 609
    mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(),   // QGC system id
                                             _mavlink->getComponentId(),     // QGC component id
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,                           // Pack into this mavlink_message_t
                                             _vehicle->id(),                 // Target system id
                                             componentId,                    // Target component id
                                             fixedParamName,                 // Named parameter being requested
                                             paramIndex);                    // Parameter index being requested, -1 for named
610
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
611 612
}

613
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
614 615 616
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
617

618
    FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type();
619
    p.param_type = _factTypeToMavType(factType);
dogmaphobic's avatar
dogmaphobic committed
620

621 622
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
623
            union_value.param_uint8 = (uint8_t)value.toUInt();
624
            break;
dogmaphobic's avatar
dogmaphobic committed
625

626
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
627
            union_value.param_int8 = (int8_t)value.toInt();
628
            break;
dogmaphobic's avatar
dogmaphobic committed
629

630
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
631
            union_value.param_uint16 = (uint16_t)value.toUInt();
632
            break;
dogmaphobic's avatar
dogmaphobic committed
633

634
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
635
            union_value.param_int16 = (int16_t)value.toInt();
636
            break;
dogmaphobic's avatar
dogmaphobic committed
637

638
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
639
            union_value.param_uint32 = (uint32_t)value.toUInt();
640
            break;
dogmaphobic's avatar
dogmaphobic committed
641

642 643 644
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
645

646 647 648
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
649

650
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
651
            union_value.param_int32 = (int32_t)value.toInt();
652 653
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
654

655
    p.param_value = union_value.param_float;
656
    p.target_system = (uint8_t)_vehicle->id();
657
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
658

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

661
    mavlink_message_t msg;
662 663 664 665 666
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      &p);
667
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
668 669
}

670
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
671
{
672
    MapID2NamedParam cache_map;
673

674 675 676 677
    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()));
678 679
    }

680
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
681 682 683 684 685 686
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

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

687
QDir ParameterManager::parameterCacheDir()
688 689 690 691 692
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

693
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
694
{
695
    return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId));
696 697
}

698
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
699 700 701
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
702
    MapID2NamedParam cache_map;
703
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
704
    if (!cache_file.exists()) {
705
        /* no local cache, just wait for them to come in*/
706 707 708 709 710 711 712 713 714
        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 */
715 716 717 718 719 720 721

    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);
722 723 724
    }

    if (crc32_value == hash_value.toUInt()) {
725
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
726
        /* if the two param set hashes match, just load from the disk */
727 728 729 730 731 732
        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);
733
            _parameterUpdate(vehicleId, componentId, name, count, id, mavType, value);
734
        }
735 736 737 738 739 740 741 742 743 744
        // 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;
745 746 747 748 749
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
                                          _vehicle->priorityLink()->mavlinkChannel(),
                                          &msg,
                                          &p);
750
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
751 752 753 754 755 756 757 758 759

        // Give the user some feedback things loaded properly
        QVariantAnimation *ani = new QVariantAnimation(this);
        ani->setEasingCurve(QEasingCurve::OutCubic);
        ani->setStartValue(0.0);
        ani->setEndValue(1.0);
        ani->setDuration(750);

        connect(ani, &QVariantAnimation::valueChanged, [this](const QVariant &value) {
760
            _setLoadProgress(value.toDouble());
761 762 763 764 765
        });

        // Hide 500ms after animation finishes
        connect(ani, &QVariantAnimation::finished, [this](){
            QTimer::singleShot(500, [this]() {
766
                _setLoadProgress(0);
767 768 769 770
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
771 772 773
    }
}

774
void ParameterManager::_saveToEEPROM(void)
775
{
776 777
    if (_saveRequired) {
        _saveRequired = false;
778
        if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
779 780 781 782 783
            _vehicle->sendMavCommand(MAV_COMP_ID_ALL,
                                     MAV_CMD_PREFLIGHT_STORAGE,
                                     true,  // showError
                                     1,     // Write parameters to EEPROM
                                     -1);   // Don't do anything with mission storage
784
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM";
785
        } else {
786
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
787
        }
Don Gagne's avatar
Don Gagne committed
788
    }
789 790
}

791
QString ParameterManager::readParametersFromStream(QTextStream& stream)
792
{
793
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
794

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

805 806 807 808
                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
809

810
                if (!parameterExists(componentId, paramName)) {
811 812 813
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
814
                    qCDebug(ParameterManagerLog) << error;
815 816
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
817

818
                Fact* fact = getParameter(componentId, paramName);
819
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
820 821 822
                    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;
823
                    qCDebug(ParameterManagerLog) << error;
824 825
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
826

827
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
828
                fact->setRawValue(valStr);
829 830 831
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
832

833
    return errors;
834 835
}

836
void ParameterManager::writeParametersToStream(QTextStream &stream)
837
{
Don Gagne's avatar
Don Gagne committed
838
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
839
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
840
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
841 842

    foreach (int componentId, _mapParameterName2Variant.keys()) {
843
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
844
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
845 846 847 848 849
            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";
            }
850 851
        }
    }
dogmaphobic's avatar
dogmaphobic committed
852

853 854 855
    stream.flush();
}

856
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
857 858 859 860
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
861

862 863
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
864

865 866
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
867

868 869
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
870

871 872
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
873

874 875
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
876

877 878 879
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
880

881 882 883 884 885
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

886
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
887 888 889 890
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
891

892 893
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
894

895 896
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
897

898 899
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
900

901 902
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
903

904 905
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
906

907 908 909
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
910

911 912 913 914 915
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

916
void ParameterManager::_addMetaDataToDefaultComponent(void)
917 918 919 920 921
{
     if (_parameterMetaData) {
         return;
     }

Don Gagne's avatar
Don Gagne committed
922
     QString metaDataFile;
923
     int majorVersion, minorVersion;
924 925 926 927

     // Load best parameter meta data set
     metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
     qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
Don Gagne's avatar
Don Gagne committed
928

929 930 931
     _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);

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

938
void ParameterManager::_checkInitialLoadComplete(void)
939 940 941 942 943
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
944

945 946 947 948 949 950
    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
951

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

955 956
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";

957 958 959 960 961 962 963 964 965 966
    // 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;
967
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
968 969
        }
    }
970 971

    _missingParameters = false;
972
    if (initialLoadFailures) {
973
        _missingParameters = true;
974
        QString errorMsg = tr("QGroundControl was unable to retrieve the full set of parameters from vehicle %1. "
dogmaphobic's avatar
dogmaphobic committed
975
                              "This will cause QGroundControl to be unable to display its full user interface. "
976
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
977 978 979
                              "If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(_vehicle->id());
        qCDebug(ParameterManagerLog) << errorMsg;
        qgcApp()->showMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
980
        if (!qgcApp()->runningUnitTests()) {
981
            qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
Don Gagne's avatar
Don Gagne committed
982
        }
983 984
    }

985
    // Signal load complete
986
    _parametersReady = true;
987 988 989
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
990
}
991

992
void ParameterManager::_initialRequestTimeout(void)
993
{
994
    if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
995
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retrying initial parameter request list";
996 997
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
998 999
    } else {
        if (!_vehicle->genericFirmware()) {
Don Gagne's avatar
Don Gagne committed
1000
            QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1001
                                  "This will cause QGroundControl to be unable to display its full user interface.").arg(_vehicle->id());
1002 1003 1004
            qCDebug(ParameterManagerLog) << errorMsg;
            qgcApp()->showMessage(errorMsg);
        }
1005
    }
1006
}
1007

1008
QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024
{
    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 {
1025
            qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
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
            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 {
1058
                qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
1059 1060 1061 1062 1063 1064
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
1065
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile(vehicle);
1066
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
1067
    qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
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
    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;
    }
1099
    qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
1100 1101 1102 1103

    return metaDataFile;
}

1104
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
1105 1106 1107 1108 1109
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
1110
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
1111 1112 1113

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
1114
    QString cacheHit = ParameterManager::parameterMetaDataFile(NULL, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
1115
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139

    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)));
1140
        qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
1141 1142 1143 1144
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1145 1146

/// Remap a parameter from one firmware version to another
1147
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158
{
    QString mappedParamName;

    if (!paramName.startsWith(QStringLiteral("r."))) {
        // No version mapping wanted
        return paramName;
    }

    int majorVersion = _vehicle->firmwareMajorVersion();
    int minorVersion = _vehicle->firmwareMinorVersion();

1159
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171

    mappedParamName = paramName.right(paramName.count() - 2);

    if (majorVersion == Vehicle::versionNotSetValue) {
        // Vehicle version unknown
        return mappedParamName;
    }

    const FirmwarePlugin::remapParamNameMajorVersionMap_t& majorVersionRemap = _vehicle->firmwarePlugin()->paramNameRemapMajorVersionMap();

    if (!majorVersionRemap.contains(majorVersion)) {
        // No mapping for this major version
1172
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1173 1174 1175 1176 1177
        return mappedParamName;
    }

    const FirmwarePlugin::remapParamNameMinorVersionRemapMap_t& remapMinorVersion = majorVersionRemap[majorVersion];

1178
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1179 1180 1181 1182 1183 1184 1185

    for (int currentMinorVersion=_vehicle->firmwarePlugin()->remapParamNameHigestMinorVersionNumber(majorVersion); currentMinorVersion>minorVersion; currentMinorVersion--) {
        if (remapMinorVersion.contains(currentMinorVersion)) {
            const FirmwarePlugin::remapParamNameMap_t& remap = remapMinorVersion[currentMinorVersion];

            if (remap.contains(mappedParamName)) {
                QString toParamName = remap[mappedParamName];
1186
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1187 1188 1189 1190 1191 1192 1193
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1194 1195

/// The offline editing vehicle can have custom loaded params bolted into it.
1196
void ParameterManager::_loadOfflineEditingParams(void)
1197 1198 1199 1200 1201 1202 1203 1204
{    
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1205
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219
    }

    QTextStream paramStream(&paramFile);

    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();

        if (line.startsWith("#")) {
            continue;
        }

        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);

1220 1221
        int defaultComponentId = paramData.at(1).toInt();
        _vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        MAV_PARAM_TYPE paramType = static_cast<MAV_PARAM_TYPE>(paramData.at(4).toUInt());

        QVariant paramValue;
        switch (paramType) {
        case MAV_PARAM_TYPE_REAL32:
            paramValue = QVariant(valStr.toFloat());
            break;
        case MAV_PARAM_TYPE_UINT32:
            paramValue = QVariant(valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT32:
            paramValue = QVariant(valStr.toInt());
            break;
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant((quint16)valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT16:
            paramValue = QVariant((qint16)valStr.toInt());
            break;
        case MAV_PARAM_TYPE_UINT8:
            paramValue = QVariant((quint8)valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT8:
            paramValue = QVariant((qint8)valStr.toUInt());
            break;
        default:
            qCritical() << "Unknown type" << paramType;
            paramValue = QVariant(valStr.toInt());
            break;
        }

1255 1256 1257 1258 1259
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1260 1261
        Fact* fact = new Fact(defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact);
1262 1263 1264
    }

    _addMetaDataToDefaultComponent();
1265
    _setupGroupMap();
1266 1267 1268
    _parametersReady = true;
    _initialLoadComplete = true;
}
1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308

void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject)
{
    QList<int>  rgCompIds;
    QStringList rgParamNames;

    if (componentId == MAV_COMP_ID_ALL) {
        rgCompIds = _mapParameterName2Variant.keys();
    } else {
        rgCompIds.append(_actualComponentId(componentId));
    }

    QJsonArray rgParams;

    // Loop over all requested component ids
    for (int i=0; i<rgCompIds.count(); i++) {
        int compId = rgCompIds[i];

        if (!_mapParameterName2Variant.contains(compId)) {
            qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson no params for compId" << compId;
            continue;
        }

        // Build list of parameter names if not specified
        if (paramsToSave.count() == 0) {
            rgParamNames = 	parameterNames(compId);
        } else {
            rgParamNames = paramsToSave;
        }

        // Loop over parameter names adding each to json array
        for (int j=0; j<rgParamNames.count(); j++) {
            QString paramName = rgParamNames[j];

            if (!parameterExists(compId, paramName)) {
                qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson param not found compId:param" << compId << paramName;
                continue;
            }

            QJsonObject paramJson;
1309
            Fact* fact = getParameter(compId, paramName);
1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367
            paramJson.insert(_jsonCompIdKey, QJsonValue(compId));
            paramJson.insert(_jsonParamNameKey, QJsonValue(fact->name()));
            paramJson.insert(_jsonParamValueKey, QJsonValue(fact->rawValue().toDouble()));

            rgParams.append(QJsonValue(paramJson));
        }
    }

    saveObject.insert(_jsonParametersKey, QJsonValue(rgParams));
}

bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
{
    QList<QJsonValue::Type> keyTypes;

    errorString.clear();

    if (required) {
        if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonParametersKey), errorString)) {
            return false;
        }
    } else if (!json.contains(_jsonParametersKey)) {
        return true;
    }

    keyTypes = { QJsonValue::Array };
    if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonParametersKey), keyTypes, errorString)) {
        return false;
    }

    QJsonArray rgParams = json[_jsonParametersKey].toArray();
    for (int i=0; i<rgParams.count(); i++) {
        QJsonValueRef paramValue = rgParams[i];

        if (!paramValue.isObject()) {
            errorString = tr("%1 key is not a json object").arg(_jsonParametersKey);
            return false;
        }
        QJsonObject param = paramValue.toObject();

        QStringList requiredKeys = { _jsonCompIdKey, _jsonParamNameKey, _jsonParamValueKey };
        if (!JsonHelper::validateRequiredKeys(param, requiredKeys, errorString)) {
            return false;
        }
        keyTypes = { QJsonValue::Double, QJsonValue::String, QJsonValue::Double };
        if (!JsonHelper::validateKeyTypes(param, requiredKeys, keyTypes, errorString)) {
            return false;
        }

        int compId = param[_jsonCompIdKey].toInt();
        QString name = param[_jsonParamNameKey].toString();
        double value = param[_jsonParamValueKey].toDouble();

        if (!parameterExists(compId, name)) {
            qCDebug(ParameterManagerLog) << "ParameterManager::loadFromJson param not found compId:param" << compId << name;
            continue;
        }

1368
        Fact* fact = getParameter(compId, name);
1369 1370 1371 1372 1373 1374
        fact->setRawValue(value);
    }

    return true;
}

1375 1376
void ParameterManager::resetAllParametersToDefaults(void)
{
1377 1378 1379 1380 1381
    _vehicle->sendMavCommand(MAV_COMP_ID_ALL,
                             MAV_CMD_PREFLIGHT_STORAGE,
                             true,  // showError
                             2,     // Reset params to default
                             -1);   // Don't do anything with mission storage
1382 1383
}

1384 1385 1386 1387 1388 1389 1390 1391
QString ParameterManager::_logVehiclePrefix(int componentId)
{
    if (componentId == -1) {
        return QString("V:%1").arg(_vehicle->id());
    } else {
        return QString("V:%1 C:%2").arg(_vehicle->id()).arg(componentId);
    }
}
1392 1393 1394 1395 1396 1397

void ParameterManager::_setLoadProgress(double loadProgress)
{
    _loadProgress = loadProgress;
    emit loadProgressChanged(loadProgress);
}