ParameterManager.cc 59.9 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
    , _defaultComponentId(MAV_COMP_ID_ALL)
56 57
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
Don Gagne's avatar
Don Gagne committed
58 59 60
    , _prevWaitingReadParamIndexCount(0)
    , _prevWaitingReadParamNameCount(0)
    , _prevWaitingWriteParamNameCount(0)
61
    , _initialRequestRetryCount(0)
62
    , _disableAllRetries(false)
63
    , _totalParamCount(0)
64
{
65 66
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

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

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

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

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

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

84
    _defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
85
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Default component param" << _defaultComponentIdParam;
86

87 88 89
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
    refreshAllParameters();
90 91
}

92
ParameterManager::~ParameterManager()
93
{
94
    delete _parameterMetaData;
95 96 97
}

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

105 106 107 108 109 110 111 112
    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
                                            "_parameterUpdate" <<
                                            "name:" << parameterName <<
                                            "count:" << parameterCount <<
                                            "index:" << parameterId <<
                                            "mavType:" << mavType <<
                                            "value:" << value <<
                                            ")";
113

114
    _initialRequestTimeoutTimer.stop();
dogmaphobic's avatar
dogmaphobic committed
115

116 117 118
#if 0
    // Handy for testing retry logic
    static int counter = 0;
119
    if (counter++ & 0x8) {
120
        qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
121 122 123
        return;
    }
#endif
124

125 126 127 128 129 130 131
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

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

    _initialRequestTimeoutTimer.stop();
139
    _waitingParamTimeoutTimer.stop();
140

141
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
142

143 144 145 146 147
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
148 149

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

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

159 160 161
        // 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
162

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

166 167
    // Determine default component id
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
168
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Default component id determined";
169 170 171 172 173 174 175 176 177
        _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;
    }

178 179 180
    if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
        !_waitingReadParamNameMap[componentId].contains(parameterName) &&
        !_waitingWriteParamNameMap[componentId].contains(parameterName)) {
181
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName;
182 183
    }

184
    // Remove this parameter from the waiting lists
185 186 187
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
188 189 190 191 192 193 194 195 196
    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];
    }
197 198

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

200 201 202
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
203

204 205 206 207
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
208
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
209 210 211 212 213 214
    }

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

218 219 220 221
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
222
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
223
    }
dogmaphobic's avatar
dogmaphobic committed
224

Don Gagne's avatar
Don Gagne committed
225 226 227
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
228 229 230 231 232 233 234 235 236 237 238
        // More params to wait for, restart timer
        _waitingParamTimeoutTimer.start();
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
    } else {
        if (_defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty()) {
            // Still waiting for default component id, restart timer
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (still waiting for default component)";
            _waitingParamTimeoutTimer.start();
        } else {
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
        }
239 240
    }

Don Gagne's avatar
Don Gagne committed
241 242 243 244 245
    // 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
246
            _setLoadProgress(0.0);
Don Gagne's avatar
Don Gagne committed
247
        }
248
    } else {
249
        _setLoadProgress((double)(_totalParamCount - readWaitingParamCount) / (double)_totalParamCount);
250
    }
dogmaphobic's avatar
dogmaphobic committed
251

252 253 254 255 256
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

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

260 261 262 263 264 265
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
266
                factType = FactMetaData::valueTypeInt8;
267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
                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
291

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

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

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

Don Gagne's avatar
Don Gagne committed
300 301
    _dataMutex.unlock();

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

304 305
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
306
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
307

308 309 310 311 312 313 314 315 316 317 318 319 320
    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();
    }

Don Gagne's avatar
Don Gagne committed
321 322
    if (_prevWaitingWriteParamNameCount != 0 &&  waitingWriteParamNameCount == 0) {
        // If all the writes just finished the vehicle is up to date, so persist.
323 324
        _saveToEEPROM();
    }
dogmaphobic's avatar
dogmaphobic committed
325

Don Gagne's avatar
Don Gagne committed
326 327 328 329 330 331
    // 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
332
            _writeLocalParamCache(vehicleId, componentId);
Don Gagne's avatar
Don Gagne committed
333 334 335 336 337 338 339
        }
    }

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

340 341
    // Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check.
    _checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
342 343

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
344 345 346 347
}

/// Connected to Fact::valueUpdated
///
348
/// Writes the parameter to mavlink, sets up for write wait
349
void ParameterManager::_valueUpdated(const QVariant& value)
350 351 352
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
353

354
    int componentId = fact->componentId();
355
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
356

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

359
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
360 361
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
362
    _waitingParamTimeoutTimer.start();
363
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
364

365
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
366

367
    _writeParameterRaw(componentId, fact->name(), value);
368
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
369

370 371
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
372
    }
373 374
}

375
void ParameterManager::refreshAllParameters(uint8_t componentId)
376
{
377
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
378

379 380 381 382
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

383
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
384
    foreach (int cid, _paramCountMap.keys()) {
385
        // Add/Update all indices to the wait list, parameter index is 0-based
386
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
387 388
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
389
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
390
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
391 392
        }
    }
dogmaphobic's avatar
dogmaphobic committed
393

394
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
395

396
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
397
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
398

399
    mavlink_message_t msg;
400 401 402 403 404
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,
                                             _vehicle->id(),
405
                                             componentId);
406
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
407

408 409
    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;
410 411
}

412
void ParameterManager::_determineDefaultComponentId(void)
413
{
414
    if (_defaultComponentId == MAV_COMP_ID_ALL) {
415 416 417
        // 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
418

419
        int largestCompParamCount = 0;
420
        foreach(int componentId, _mapParameterName2Variant.keys()) {
421 422 423
            int compParamCount = _mapParameterName2Variant[componentId].count();
            if (compParamCount > largestCompParamCount) {
                largestCompParamCount = compParamCount;
424 425 426
                _defaultComponentId = componentId;
            }
        }
427

428
        if (_defaultComponentId == MAV_COMP_ID_ALL) {
429
            qWarning() << _logVehiclePrefix() << "All parameters missing, unable to determine default component id";
430
        }
431 432 433 434
    }
}

/// Translates FactSystem::defaultComponentId to real component id if needed
435
int ParameterManager::_actualComponentId(int componentId)
436 437 438
{
    if (componentId == FactSystem::defaultComponentId) {
        componentId = _defaultComponentId;
Don Gagne's avatar
Don Gagne committed
439
        if (componentId == FactSystem::defaultComponentId) {
440
            qWarning() << _logVehiclePrefix() << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
441
        }
442
    }
dogmaphobic's avatar
dogmaphobic committed
443

444 445 446
    return componentId;
}

447
void ParameterManager::refreshParameter(int componentId, const QString& name)
448
{
449
    componentId = _actualComponentId(componentId);
450
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
451

452 453 454
    _dataMutex.lock();

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

456
    if (_waitingReadParamNameMap.contains(componentId)) {
457 458 459 460
        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
461 462
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
463
    }
dogmaphobic's avatar
dogmaphobic committed
464

465 466 467
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
468 469
}

470
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
471 472
{
    componentId = _actualComponentId(componentId);
473
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
474

475
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
476 477 478 479 480 481
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

482
bool ParameterManager::parameterExists(int componentId, const QString&  name)
483
{
484
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
485

486 487
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
488
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
489
    }
490 491

    return ret;
492 493
}

494
Fact* ParameterManager::getParameter(int componentId, const QString& name)
495 496
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
497

498 499 500
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
501
        return &_defaultFact;
502
    }
dogmaphobic's avatar
dogmaphobic committed
503

504
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
505
}
506

507
QStringList ParameterManager::parameterNames(int componentId)
508
{
dogmaphobic's avatar
dogmaphobic committed
509 510
    QStringList names;

511
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
512 513 514 515
        names << paramName;
    }

    return names;
516 517
}

518
void ParameterManager::_setupGroupMap(void)
519
{
520 521 522
    // Must be able to handle being called multiple times
    _mapGroup2ParameterName.clear();

523
    foreach (int componentId, _mapParameterName2Variant.keys()) {
524
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
525 526 527 528 529 530
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

531
const QMap<int, QMap<QString, QStringList> >& ParameterManager::getGroupMap(void)
532 533 534
{
    return _mapGroup2ParameterName;
}
535

536
void ParameterManager::_waitingParamTimeout(void)
537 538 539 540
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
dogmaphobic's avatar
dogmaphobic committed
541

542 543
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout";

544
    // First check for any missing parameters from the initial index based load
545

546 547
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
548 549 550 551 552 553 554 555 556
        if (_waitingReadParamIndexMap[componentId].count()) {
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
        }

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

557
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
558
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
559 560
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
561
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
562 563 564 565 566
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
                paramsRequested = true;
                _readParameterRaw(componentId, "", paramIndex);
567
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
568 569 570
            }
        }
    }
571

572
    if (!paramsRequested && _defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty() && !_waitingForDefaultComponent) {
573 574
        // 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.
575
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component id";
576 577 578 579 580 581 582 583
        _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
584

585 586
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
587
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
588
                paramsRequested = true;
589
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
590
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
591
                    _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
592
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
593 594 595 596 597 598
                    if (++batchCount > maxBatchSize) {
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
599 600 601
                    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);
602 603 604 605
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
606

607 608
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
609
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
610
                paramsRequested = true;
611
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
612 613
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
614
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
615 616 617 618 619 620
                    if (++batchCount > maxBatchSize) {
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
621 622 623
                    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);
624 625 626 627
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
628

629 630
Out:
    if (paramsRequested) {
631
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request";
632 633 634 635
        _waitingParamTimeoutTimer.start();
    }
}

636
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
637 638 639 640 641
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
642 643 644 645 646 647 648 649
    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
650
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
651 652
}

653
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
654 655 656
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
657

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

661 662
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
663
            union_value.param_uint8 = (uint8_t)value.toUInt();
664
            break;
dogmaphobic's avatar
dogmaphobic committed
665

666
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
667
            union_value.param_int8 = (int8_t)value.toInt();
668
            break;
dogmaphobic's avatar
dogmaphobic committed
669

670
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
671
            union_value.param_uint16 = (uint16_t)value.toUInt();
672
            break;
dogmaphobic's avatar
dogmaphobic committed
673

674
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
675
            union_value.param_int16 = (int16_t)value.toInt();
676
            break;
dogmaphobic's avatar
dogmaphobic committed
677

678
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
679
            union_value.param_uint32 = (uint32_t)value.toUInt();
680
            break;
dogmaphobic's avatar
dogmaphobic committed
681

682 683 684
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
685

686 687 688
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
689

690
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
691
            union_value.param_int32 = (int32_t)value.toInt();
692 693
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
694

695
    p.param_value = union_value.param_float;
696
    p.target_system = (uint8_t)_vehicle->id();
697
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
698

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

701
    mavlink_message_t msg;
702 703 704 705 706
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      &p);
707
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
708 709
}

710
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
711
{
712
    MapID2NamedParam cache_map;
713

714 715 716 717
    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()));
718 719
    }

720
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
721 722 723 724 725 726
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

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

727
QDir ParameterManager::parameterCacheDir()
728 729 730 731 732
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

733
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
734
{
735
    return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId));
736 737
}

738
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
739 740 741
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
742
    MapID2NamedParam cache_map;
743
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
744
    if (!cache_file.exists()) {
745
        /* no local cache, just wait for them to come in*/
746 747 748 749 750 751 752 753 754
        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 */
755 756 757 758 759 760 761

    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);
762 763 764
    }

    if (crc32_value == hash_value.toUInt()) {
765
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
766
        /* if the two param set hashes match, just load from the disk */
767 768 769 770 771 772
        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);
773
            _parameterUpdate(vehicleId, componentId, name, count, id, mavType, value);
774
        }
775 776 777 778 779 780 781 782 783 784
        // 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;
785 786 787 788 789
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
                                          _vehicle->priorityLink()->mavlinkChannel(),
                                          &msg,
                                          &p);
790
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
791 792 793 794 795 796 797 798 799

        // 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) {
800
            _setLoadProgress(value.toDouble());
801 802 803 804 805
        });

        // Hide 500ms after animation finishes
        connect(ani, &QVariantAnimation::finished, [this](){
            QTimer::singleShot(500, [this]() {
806
                _setLoadProgress(0);
807 808 809 810
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
811 812 813
    }
}

814
void ParameterManager::_saveToEEPROM(void)
815
{
816 817
    if (_saveRequired) {
        _saveRequired = false;
818
        if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
819 820 821 822 823
            _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
824
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM";
825
        } else {
826
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
827
        }
Don Gagne's avatar
Don Gagne committed
828
    }
829 830
}

831
QString ParameterManager::readParametersFromStream(QTextStream& stream)
832
{
833
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
834

835 836 837 838 839 840
    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
841 842
                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
843 844
                }

845 846 847 848
                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
849

850
                if (!parameterExists(componentId, paramName)) {
851 852 853
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
854
                    qCDebug(ParameterManagerLog) << error;
855 856
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
857

858
                Fact* fact = getParameter(componentId, paramName);
859
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
860 861 862
                    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;
863
                    qCDebug(ParameterManagerLog) << error;
864 865
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
866

867
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
868
                fact->setRawValue(valStr);
869 870 871
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
872

873
    return errors;
874 875
}

876
void ParameterManager::writeParametersToStream(QTextStream &stream)
877
{
Don Gagne's avatar
Don Gagne committed
878
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
879
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
880
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
881 882

    foreach (int componentId, _mapParameterName2Variant.keys()) {
883
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
884
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
885 886 887 888 889
            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";
            }
890 891
        }
    }
dogmaphobic's avatar
dogmaphobic committed
892

893 894 895
    stream.flush();
}

896
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
897 898 899 900
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
901

902 903
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
904

905 906
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
907

908 909
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
910

911 912
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
913

914 915
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
916

917 918 919
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
920

921 922 923 924 925
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

926
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
927 928 929 930
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
931

932 933
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
934

935 936
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
937

938 939
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
940

941 942
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
943

944 945
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
946

947 948 949
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
950

951 952 953 954 955
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

956
void ParameterManager::_addMetaDataToDefaultComponent(void)
957
{
958
     if (_defaultComponentId == MAV_COMP_ID_ALL) {
959 960 961 962 963 964 965 966
         // We don't know what the default component is so we can't support meta data
         return;
     }

     if (_parameterMetaData) {
         return;
     }

Don Gagne's avatar
Don Gagne committed
967
     QString metaDataFile;
968
     int majorVersion, minorVersion;
969 970 971 972

     // 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
973

974 975 976 977 978 979 980 981 982
     _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);

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

983
/// @param failIfNoDefaultComponent true: Fails parameter load if no default component but we should have one
984
void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
985 986 987 988 989
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
990

991 992 993 994 995 996
    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
997

998
    if (!failIfNoDefaultComponent && _defaultComponentId == MAV_COMP_ID_ALL  && !_defaultComponentIdParam.isEmpty()) {
999 1000 1001 1002
        // We are still waiting for default component to show up
        return;
    }

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

1006 1007
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";

1008 1009 1010 1011 1012 1013 1014 1015 1016 1017
    // 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;
1018
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1019 1020
        }
    }
1021 1022

    _missingParameters = false;
1023
    if (initialLoadFailures) {
1024
        _missingParameters = true;
1025
        QString errorMsg = tr("QGroundControl was unable to retrieve the full set of parameters from vehicle %1. "
dogmaphobic's avatar
dogmaphobic committed
1026
                              "This will cause QGroundControl to be unable to display its full user interface. "
1027
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1028 1029 1030
                              "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
1031
        if (!qgcApp()->runningUnitTests()) {
1032
            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
1033
        }
1034
    } else if (_defaultComponentId == MAV_COMP_ID_ALL && !_defaultComponentIdParam.isEmpty()) {
1035 1036
        // Missing default component when we should have one
        _missingParameters = true;
1037
        QString errorMsg = tr("QGroundControl did not receive parameters from the default component for vehicle %1. "
1038 1039
                              "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. "
1040 1041 1042
                              "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
1043
        if (!qgcApp()->runningUnitTests()) {
1044
            qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "Default component was never found, param:" << _defaultComponentIdParam;
Don Gagne's avatar
Don Gagne committed
1045
        }
1046 1047
    }

1048
    // Signal load complete
1049 1050
    _parametersReady = true;
    _determineDefaultComponentId();
1051 1052 1053
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1054
}
1055

1056
void ParameterManager::_initialRequestTimeout(void)
1057
{
1058
    if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
1059
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retyring initial parameter request list";
1060 1061
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
1062 1063 1064
    } else {
        if (!_vehicle->genericFirmware()) {
            // Generic vehicles (like BeBop) may not have any parameters, so don't annoy the user
Don Gagne's avatar
Don Gagne committed
1065
            QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1066
                                  "This will cause QGroundControl to be unable to display its full user interface.").arg(_vehicle->id());
1067 1068 1069
            qCDebug(ParameterManagerLog) << errorMsg;
            qgcApp()->showMessage(errorMsg);
        }
1070
    }
1071
}
1072

1073
QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089
{
    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 {
1090
            qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
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
            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 {
1123
                qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
1124 1125 1126 1127 1128 1129
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
1130
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile(vehicle);
1131
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
1132
    qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163
    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;
    }
1164
    qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
1165 1166 1167 1168

    return metaDataFile;
}

1169
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
1170 1171 1172 1173 1174
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
1175
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
1176 1177 1178

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
1179
    QString cacheHit = ParameterManager::parameterMetaDataFile(NULL, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
1180
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204

    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)));
1205
        qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
1206 1207 1208 1209
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1210 1211

/// Remap a parameter from one firmware version to another
1212
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223
{
    QString mappedParamName;

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

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

1224
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236

    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
1237
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1238 1239 1240 1241 1242
        return mappedParamName;
    }

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

1243
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1244 1245 1246 1247 1248 1249 1250

    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];
1251
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1252 1253 1254 1255 1256 1257 1258
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1259 1260

/// The offline editing vehicle can have custom loaded params bolted into it.
1261
void ParameterManager::_loadOfflineEditingParams(void)
1262 1263 1264 1265 1266 1267 1268 1269
{    
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1270
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
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 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318
    }

    QTextStream paramStream(&paramFile);

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

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

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

        _defaultComponentId = paramData.at(1).toInt();
        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;
        }

1319 1320 1321 1322 1323
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1324 1325 1326 1327 1328
        Fact* fact = new Fact(_defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[_defaultComponentId][paramName] = QVariant::fromValue(fact);
    }

    _addMetaDataToDefaultComponent();
1329
    _setupGroupMap();
1330 1331 1332
    _parametersReady = true;
    _initialLoadComplete = true;
}
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 1368 1369 1370 1371 1372

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;
1373
            Fact* fact = getParameter(compId, paramName);
1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431
            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;
        }

1432
        Fact* fact = getParameter(compId, name);
1433 1434 1435 1436 1437 1438
        fact->setRawValue(value);
    }

    return true;
}

1439 1440
void ParameterManager::resetAllParametersToDefaults(void)
{
1441 1442 1443 1444 1445
    _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
1446 1447
}

1448 1449 1450 1451 1452 1453 1454 1455
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);
    }
}
1456 1457 1458 1459 1460 1461

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