ParameterManager.cc 63.2 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
#include "ParameterManager.h"
11 12
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
13
#include "QGCApplication.h"
14
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
15
#include "FirmwarePlugin.h"
16
#include "UAS.h"
17
#include "JsonHelper.h"
18

19
#include <QEasingCurve>
20 21
#include <QFile>
#include <QDebug>
22
#include <QVariantAnimation>
23
#include <QJsonArray>
24

25 26 27
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log,           "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log,           "ParameterManagerVerbose2Log")
QGC_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog,  "ParameterManagerDebugCacheFailureLog") // Turn on to debug parameter cache crc misses
28

29
Fact ParameterManager::_defaultFact;
Don Gagne's avatar
Don Gagne committed
30

31 32 33 34 35
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";
36

37
ParameterManager::ParameterManager(Vehicle* vehicle)
38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57
    : QObject                           (vehicle)
    , _vehicle                          (vehicle)
    , _mavlink                          (NULL)
    , _loadProgress                     (0.0)
    , _parametersReady                  (false)
    , _missingParameters                (false)
    , _initialLoadComplete              (false)
    , _waitingForDefaultComponent       (false)
    , _saveRequired                     (false)
    , _metaDataAddedToFacts             (false)
    , _logReplay                        (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay())
    , _parameterSetMajorVersion         (-1)
    , _parameterMetaData                (NULL)
    , _prevWaitingReadParamIndexCount   (0)
    , _prevWaitingReadParamNameCount    (0)
    , _prevWaitingWriteParamNameCount   (0)
    , _initialRequestRetryCount         (0)
    , _disableAllRetries                (false)
    , _indexBatchQueueActive            (false)
    , _totalParamCount                  (0)
58
{
59 60
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

61 62 63 64 65 66
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

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

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

72
    _waitingParamTimeoutTimer.setSingleShot(true);
73
    _waitingParamTimeoutTimer.setInterval(3000);
74
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
75

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

78 79
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
Don Gagne's avatar
Don Gagne committed
80

81 82 83 84 85 86 87 88
    if (_vehicle->highLatencyLink()) {
        // High latency links don't load parameters
        _parametersReady = true;
        _missingParameters = true;
        _initialLoadComplete = true;
        _waitingForDefaultComponent = false;
        emit parametersReadyChanged(_parametersReady);
        emit missingParametersChanged(_missingParameters);
89
    } else if (!_logReplay){
90 91
        refreshAllParameters();
    }
92 93
}

94
ParameterManager::~ParameterManager()
95
{
96
    delete _parameterMetaData;
97 98 99
}

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

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

116 117
    // ArduPilot has this strange behavior of streaming parameters that we didn't ask for. This even happens before it responds to the
    // PARAM_REQUEST_LIST. We disregard any of this until the initial request is responded to.
118
    if (parameterId == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
Patrick José Pereira's avatar
Patrick José Pereira committed
119
        qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to initial list response" << parameterName;
120 121 122
        return;
    }

123
    _initialRequestTimeoutTimer.stop();
dogmaphobic's avatar
dogmaphobic committed
124

125
#if 0
126 127 128 129 130 131 132
    if (!_initialLoadComplete && !_indexBatchQueueActive) {
        // Handy for testing retry logic
        static int counter = 0;
        if (counter++ & 0x8) {
            qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
            return;
        }
133 134
    }
#endif
135

136 137 138 139 140 141 142
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

143 144 145 146 147 148
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
        if (!_initialLoadComplete && !_logReplay) {
            /* we received a cache hash, potentially load from cache */
            _tryCacheHashLoad(vehicleId, componentId, value);
        }
        return;
149
    }
150

151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168
    // Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog)
    if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
        if (_debugCacheMap[componentId].contains(parameterName)) {
            const ParamTypeVal& cacheParamTypeVal = _debugCacheMap[componentId][parameterName];
            size_t dataSize = FactMetaData::typeToSize(static_cast<FactMetaData::ValueType_t>(cacheParamTypeVal.first));
            const void *cacheData = cacheParamTypeVal.second.constData();

            const void *vehicleData = value.constData();

            if (memcmp(cacheData, vehicleData, dataSize)) {
                qDebug() << "Cache/Vehicle values differ for name:cache:actual" << parameterName << value << cacheParamTypeVal.second;
            }
            _debugCacheParamSeen[componentId][parameterName] = true;
        } else {
            qDebug() << "Parameter missing from cache" << parameterName;
        }
    }

169
    _initialRequestTimeoutTimer.stop();
170
    _waitingParamTimeoutTimer.stop();
171

172
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
173

174 175 176 177 178
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
179

180 181
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
182 183 184 185
        // 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;
186
        }
dogmaphobic's avatar
dogmaphobic committed
187

188 189 190
        // 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
191

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

195 196 197 198 199 200
    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;
    }

201
    if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
202 203
            !_waitingReadParamNameMap[componentId].contains(parameterName) &&
            !_waitingWriteParamNameMap[componentId].contains(parameterName)) {
204
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName;
205 206
    }

207
    // Remove this parameter from the waiting lists
208 209 210 211 212
    if (_waitingReadParamIndexMap[componentId].contains(parameterId)) {
        _waitingReadParamIndexMap[componentId].remove(parameterId);
        _indexBatchQueue.removeOne(parameterId);
        _fillIndexBatchQueue(false /* waitingParamTimeout */);
    }
213 214
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
215 216 217 218 219 220 221 222 223
    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];
    }
224 225

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

227 228 229
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
230

231 232 233 234
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
235
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
236 237 238 239 240 241
    }

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

245 246 247 248
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
249
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
250
    }
dogmaphobic's avatar
dogmaphobic committed
251

Don Gagne's avatar
Don Gagne committed
252 253 254
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
255 256 257 258
        // More params to wait for, restart timer
        _waitingParamTimeoutTimer.start();
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
    } else {
259 260 261 262 263 264 265
        if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
            // Still waiting for parameters from default component
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
            _waitingParamTimeoutTimer.start();
        } else {
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
        }
266 267
    }

Don Gagne's avatar
Don Gagne committed
268 269 270 271 272
    // 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
273
            _setLoadProgress(0.0);
Don Gagne's avatar
Don Gagne committed
274
        }
275
    } else {
276
        _setLoadProgress((double)(_totalParamCount - readWaitingParamCount) / (double)_totalParamCount);
277
    }
dogmaphobic's avatar
dogmaphobic committed
278

279 280 281 282 283
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

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

287 288
        FactMetaData::ValueType_t factType;
        switch (mavType) {
289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306
        case MAV_PARAM_TYPE_UINT8:
            factType = FactMetaData::valueTypeUint8;
            break;
        case MAV_PARAM_TYPE_INT8:
            factType = FactMetaData::valueTypeInt8;
            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;
307 308 309 310 311 312
        case MAV_PARAM_TYPE_UINT64:
            factType = FactMetaData::valueTypeUint64;
            break;
        case MAV_PARAM_TYPE_INT64:
            factType = FactMetaData::valueTypeInt64;
            break;
313 314 315 316 317 318 319 320 321 322
        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;
323
        }
dogmaphobic's avatar
dogmaphobic committed
324

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

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

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

Don Gagne's avatar
Don Gagne committed
333 334
    _dataMutex.unlock();

DonLakeFlyer's avatar
DonLakeFlyer committed
335 336 337 338 339 340 341 342 343
    Fact* fact = NULL;
    if (_mapParameterName2Variant[componentId].contains(parameterName)) {
        fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    }
    if (fact) {
        fact->_containerSetRawValue(value);
    } else {
        qWarning() << "Internal error";
    }
dogmaphobic's avatar
dogmaphobic committed
344

345
    if (componentParamsComplete) {
346
        if (componentId == _vehicle->defaultComponentId()) {
347 348 349 350 351 352 353 354
            // 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.
355
        _setupCategoryMap();
356 357
    }

Don Gagne's avatar
Don Gagne committed
358 359 360
    // 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.
361
    if (!_logReplay && _vehicle->px4Firmware()) {
Don Gagne's avatar
Don Gagne committed
362 363
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
            // All reads just finished, update the cache
364
            _writeLocalParamCache(vehicleId, componentId);
Don Gagne's avatar
Don Gagne committed
365 366 367 368 369 370 371
        }
    }

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

372
    _checkInitialLoadComplete();
373 374

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
375 376 377 378
}

/// Connected to Fact::valueUpdated
///
379
/// Writes the parameter to mavlink, sets up for write wait
380
void ParameterManager::_valueUpdated(const QVariant& value)
381 382
{
    Fact* fact = qobject_cast<Fact*>(sender());
DonLakeFlyer's avatar
DonLakeFlyer committed
383 384 385 386
    if (!fact) {
        qWarning() << "Internal error";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
387

388
    int componentId = fact->componentId();
389
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
390

391
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
392

DonLakeFlyer's avatar
DonLakeFlyer committed
393 394 395 396 397 398 399 400
    if (_waitingWriteParamNameMap.contains(componentId)) {
        _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
        _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
        _waitingParamTimeoutTimer.start();
        _saveRequired = true;
    } else {
        qWarning() << "Internal error";
    }
dogmaphobic's avatar
dogmaphobic committed
401

402
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
403

404
    _writeParameterRaw(componentId, fact->name(), value);
405
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
406

407
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
408
        qgcApp()->showMessage(tr("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
409
    }
410 411
}

412
void ParameterManager::refreshAllParameters(uint8_t componentId)
413
{
Don Gagne's avatar
Don Gagne committed
414 415 416 417
    if (_logReplay) {
        return;
    }

418
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
419

420 421 422 423
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

424
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
425
    foreach (int cid, _paramCountMap.keys()) {
426
        // Add/Update all indices to the wait list, parameter index is 0-based
427
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
428 429
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
430
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
431
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
432 433
        }
    }
dogmaphobic's avatar
dogmaphobic committed
434

435
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
436

437
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
dogmaphobic's avatar
dogmaphobic committed
438

439
    mavlink_message_t msg;
440 441 442 443 444
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,
                                             _vehicle->id(),
445
                                             componentId);
446
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
447

448 449
    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;
450 451 452
}

/// Translates FactSystem::defaultComponentId to real component id if needed
453
int ParameterManager::_actualComponentId(int componentId)
454 455
{
    if (componentId == FactSystem::defaultComponentId) {
456
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
457
        if (componentId == FactSystem::defaultComponentId) {
458
            qWarning() << _logVehiclePrefix() << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
459
        }
460
    }
dogmaphobic's avatar
dogmaphobic committed
461

462 463 464
    return componentId;
}

465
void ParameterManager::refreshParameter(int componentId, const QString& name)
466
{
467
    componentId = _actualComponentId(componentId);
468
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
469

470 471 472
    _dataMutex.lock();

    if (_waitingReadParamNameMap.contains(componentId)) {
473 474 475 476
        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
477 478
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
479 480
    } else {
        qWarning() << "Internal error";
481
    }
dogmaphobic's avatar
dogmaphobic committed
482

483 484 485
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
486 487
}

488
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
489 490
{
    componentId = _actualComponentId(componentId);
491
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
492

493
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
494 495 496 497 498 499
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

500
bool ParameterManager::parameterExists(int componentId, const QString&  name)
501
{
502
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
503

504 505
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
506
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
507
    }
508 509

    return ret;
510 511
}

512
Fact* ParameterManager::getParameter(int componentId, const QString& name)
513 514
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
515

516 517 518
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
519
        return &_defaultFact;
520
    }
dogmaphobic's avatar
dogmaphobic committed
521

522
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
523
}
524

525
QStringList ParameterManager::parameterNames(int componentId)
526
{
dogmaphobic's avatar
dogmaphobic committed
527 528
    QStringList names;

529
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
530 531 532 533
        names << paramName;
    }

    return names;
534 535
}

536
void ParameterManager::_setupCategoryMap(void)
537
{
538
    // Must be able to handle being called multiple times
539
    _categoryMap.clear();
540

541 542 543
    foreach (const QString &name, _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
        Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value<Fact*>();
        _categoryMap[fact->category()][fact->group()] += name;
544 545 546
    }
}

547
const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getCategoryMap(void)
548
{
549
    return _categoryMap;
550
}
551

552 553 554 555
/// Requests missing index based parameters from the vehicle.
///     @param waitingParamTimeout: true: being called due to timeout, false: being called to re-fill the batch queue
/// return true: Parameters were requested, false: No more requests needed
bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout)
556
{
557 558 559
    if (!_indexBatchQueueActive) {
        return false;
    }
dogmaphobic's avatar
dogmaphobic committed
560

561
    const int maxBatchSize = 10;
562

563 564 565 566 567 568 569
    if (waitingParamTimeout) {
        // We timed out, clear the queue and try again
        qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to timeout";
        _indexBatchQueue.clear();
    } else {
        qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to received parameter";
    }
570

571
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
572
        if (_waitingReadParamIndexMap[componentId].count()) {
573 574
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
575 576
        }

577 578 579 580 581 582 583 584
        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
            if (_indexBatchQueue.contains(paramIndex)) {
                // Don't add more than once
                continue;
            }

            if (_indexBatchQueue.count() > maxBatchSize) {
                break;
585 586
            }

587
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
588
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
589 590
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
591
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
592 593 594
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
595
                _indexBatchQueue.append(paramIndex);
596
                _readParameterRaw(componentId, "", paramIndex);
597
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
598 599 600
            }
        }
    }
601

602 603 604 605 606
    return _indexBatchQueue.count() != 0;
}

void ParameterManager::_waitingParamTimeout(void)
{
607 608 609 610
    if (_logReplay) {
        return;
    }

611 612 613 614 615 616 617 618 619 620 621 622
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;

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

    // Now that we have timed out for possibly the first time we can activate the index batch queue
    _indexBatchQueueActive = true;

    // First check for any missing parameters from the initial index based load
    paramsRequested = _fillIndexBatchQueue(true /* waitingParamTimeout */);

623 624 625
    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.
626
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
627 628 629 630 631 632
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

633
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
634

635 636
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
637
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
638
                paramsRequested = true;
639
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
640
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
641
                    _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
642
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
643
                    if (++batchCount > maxBatchSize) {
644 645 646 647 648
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
649 650 651
                    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);
652 653 654 655
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
656

657 658
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
659
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
660
                paramsRequested = true;
661
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
662 663
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
664
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
665
                    if (++batchCount > maxBatchSize) {
666 667 668 669 670
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
671 672 673
                    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);
674 675 676 677
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
678

679 680
Out:
    if (paramsRequested) {
681
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request";
682 683 684 685
        _waitingParamTimeoutTimer.start();
    }
}

686
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
687 688 689 690 691
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
692 693 694 695 696 697 698 699
    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
700
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
701 702
}

703
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
704 705 706
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
707

Don Gagne's avatar
Don Gagne committed
708 709
    memset(&p, 0, sizeof(p));

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

713
    switch (factType) {
714 715 716
    case FactMetaData::valueTypeUint8:
        union_value.param_uint8 = (uint8_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
717

718 719 720
    case FactMetaData::valueTypeInt8:
        union_value.param_int8 = (int8_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
721

722 723 724
    case FactMetaData::valueTypeUint16:
        union_value.param_uint16 = (uint16_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
725

726 727 728
    case FactMetaData::valueTypeInt16:
        union_value.param_int16 = (int16_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
729

730 731 732
    case FactMetaData::valueTypeUint32:
        union_value.param_uint32 = (uint32_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
733

734 735 736
    case FactMetaData::valueTypeFloat:
        union_value.param_float = value.toFloat();
        break;
dogmaphobic's avatar
dogmaphobic committed
737

738 739 740
    default:
        qCritical() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
741

742 743 744
    case FactMetaData::valueTypeInt32:
        union_value.param_int32 = (int32_t)value.toInt();
        break;
745
    }
dogmaphobic's avatar
dogmaphobic committed
746

747
    p.param_value = union_value.param_float;
748
    p.target_system = (uint8_t)_vehicle->id();
749
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
750

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

753
    mavlink_message_t msg;
754 755 756 757 758
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      &p);
759
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
760 761
}

762
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
763
{
764
    CacheMapName2ParamTypeVal cacheMap;
765

766
    foreach(const QString& name, _mapParameterName2Variant[componentId].keys()) {
767
        const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
768
        cacheMap[name] = ParamTypeVal(fact->type(), fact->rawValue());
769 770
    }

771 772
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
773

774 775
    QDataStream ds(&cacheFile);
    ds << cacheMap;
776 777
}

778
QDir ParameterManager::parameterCacheDir()
779 780 781 782 783
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

784
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
785
{
786
    return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
787 788
}

789
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
790
{
791 792
    qCInfo(ParameterManagerLog) << "Attemping load from cache";

793 794
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
795 796 797
    CacheMapName2ParamTypeVal cacheMap;
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    if (!cacheFile.exists()) {
798
        /* no local cache, just wait for them to come in*/
799 800
        return;
    }
801
    cacheFile.open(QIODevice::ReadOnly);
802 803

    /* Deserialize the parameter cache table */
804 805 806 807 808 809 810 811 812
    QDataStream ds(&cacheFile);
    ds >> cacheMap;

    // Load parameter meta data for the version number stored in cache.
    // We need meta data so we have access to the volatile bit
    if (cacheMap.contains(_versionParam)) {
        _parameterSetMajorVersion = cacheMap[_versionParam].second.toInt();
    }
    _loadMetaData();
813 814

    /* compute the crc of the local cache to check against the remote */
815

816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834
    FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin();
    foreach (const QString& name, cacheMap.keys()) {
        bool volatileValue = false;

        FactMetaData* metaData = firmwarePlugin->getMetaDataForFact(_parameterMetaData, name, _vehicle->vehicleType());
        if (metaData) {
            volatileValue = metaData->volatileValue();
        }

        if (volatileValue) {
            // Does not take part in CRC
            qCDebug(ParameterManagerLog) << "Volatile parameter" << name;
        } else {
            const ParamTypeVal& paramTypeVal = cacheMap[name];
            const void *vdat = paramTypeVal.second.constData();
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.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);
        }
835 836
    }

837
    /* if the two param set hashes match, just load from the disk */
838
    if (crc32_value == hash_value.toUInt()) {
839 840 841 842 843 844 845
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());

        int count = cacheMap.count();
        int index = 0;
        foreach (const QString& name, cacheMap.keys()) {
            const ParamTypeVal& paramTypeVal = cacheMap[name];
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
846
            const int mavType = _factTypeToMavType(fact_type);
847
            _parameterUpdate(vehicleId, componentId, name, count, index++, mavType, paramTypeVal.second);
848
        }
849

850 851 852
        // Return the hash value to notify we don't want any more updates
        mavlink_param_set_t     p;
        mavlink_param_union_t   union_value;
Don Gagne's avatar
Don Gagne committed
853
        memset(&p, 0, sizeof(p));
854 855 856 857 858 859 860
        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;
861 862 863 864 865
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
                                          _vehicle->priorityLink()->mavlinkChannel(),
                                          &msg,
                                          &p);
866
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
867 868 869 870 871 872 873 874 875

        // 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) {
876
            _setLoadProgress(value.toDouble());
877 878 879 880 881
        });

        // Hide 500ms after animation finishes
        connect(ani, &QVariantAnimation::finished, [this](){
            QTimer::singleShot(500, [this]() {
882
                _setLoadProgress(0);
883 884 885 886
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
DonLakeFlyer's avatar
DonLakeFlyer committed
887
    } else {
888 889 890 891
        // Cache parameter version may differ from vehicle parameter version so we can't trust information loaded from cache parameter version number
        _parameterSetMajorVersion = -1;
        _clearMetaData();
        qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
892 893 894 895 896 897 898
        if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
            _debugCacheCRC[componentId] = true;
            _debugCacheMap[componentId] = cacheMap;
            foreach (const QString& name, cacheMap.keys()) {
                _debugCacheParamSeen[componentId][name] = false;
            }
            qgcApp()->showMessage(tr("Parameter cache CRC match failed"));
899
        }
Don Gagne's avatar
Don Gagne committed
900
    }
901 902
}

903
QString ParameterManager::readParametersFromStream(QTextStream& stream)
904
{
905
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
906

907 908 909 910 911 912
    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
913 914
                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
915 916
                }

917 918 919 920
                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
921

922
                if (!parameterExists(componentId, paramName)) {
923 924 925
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
926
                    qCDebug(ParameterManagerLog) << error;
927 928
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
929

930
                Fact* fact = getParameter(componentId, paramName);
931
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
932 933 934
                    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;
935
                    qCDebug(ParameterManagerLog) << error;
936 937
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
938

939
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
940
                fact->setRawValue(valStr);
941 942 943
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
944

945
    return errors;
946 947
}

948
void ParameterManager::writeParametersToStream(QTextStream &stream)
949
{
Don Gagne's avatar
Don Gagne committed
950
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
951 952 953 954 955 956 957 958 959 960 961
    stream << "#\n";

    stream << "# Stack: " << _vehicle->firmwareTypeString() << "\n";
    stream << "# Vehicle: " << _vehicle->vehicleTypeString() << "\n";
    stream << "# Version: "
           << _vehicle->firmwareMajorVersion() << "."
           << _vehicle->firmwareMinorVersion() << "."
           << _vehicle->firmwarePatchVersion() << " "
           << _vehicle->firmwareVersionTypeString() << "\n";
    stream << "# Git Revision: " << _vehicle->gitHash() << "\n";

962
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
963
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
964 965

    foreach (int componentId, _mapParameterName2Variant.keys()) {
966
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
967
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
968 969 970 971 972
            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";
            }
973 974
        }
    }
dogmaphobic's avatar
dogmaphobic committed
975

976 977 978
    stream.flush();
}

979
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
980 981
{
    switch (factType) {
982 983
    case FactMetaData::valueTypeUint8:
        return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
984

985 986
    case FactMetaData::valueTypeInt8:
        return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
987

988 989
    case FactMetaData::valueTypeUint16:
        return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
990

991 992
    case FactMetaData::valueTypeInt16:
        return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
993

994 995
    case FactMetaData::valueTypeUint32:
        return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
996

997 998 999 1000 1001 1002
    case FactMetaData::valueTypeUint64:
        return MAV_PARAM_TYPE_UINT64;

    case FactMetaData::valueTypeInt64:
        return MAV_PARAM_TYPE_INT64;

1003 1004
    case FactMetaData::valueTypeFloat:
        return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
1005

1006 1007 1008
    case FactMetaData::valueTypeDouble:
        return MAV_PARAM_TYPE_REAL64;

1009 1010 1011
    default:
        qWarning() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1012

1013 1014
    case FactMetaData::valueTypeInt32:
        return MAV_PARAM_TYPE_INT32;
1015 1016 1017
    }
}

1018
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
1019 1020
{
    switch (mavType) {
1021 1022
    case MAV_PARAM_TYPE_UINT8:
        return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
1023

1024 1025
    case MAV_PARAM_TYPE_INT8:
        return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
1026

1027 1028
    case MAV_PARAM_TYPE_UINT16:
        return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
1029

1030 1031
    case MAV_PARAM_TYPE_INT16:
        return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
1032

1033 1034
    case MAV_PARAM_TYPE_UINT32:
        return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
1035

1036 1037 1038 1039 1040 1041
    case MAV_PARAM_TYPE_UINT64:
        return FactMetaData::valueTypeUint64;

    case MAV_PARAM_TYPE_INT64:
        return FactMetaData::valueTypeInt64;

1042 1043
    case MAV_PARAM_TYPE_REAL32:
        return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
1044

1045 1046 1047
    case MAV_PARAM_TYPE_REAL64:
        return FactMetaData::valueTypeDouble;

1048 1049 1050
    default:
        qWarning() << "Unsupported mav param type" << mavType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1051

1052 1053
    case MAV_PARAM_TYPE_INT32:
        return FactMetaData::valueTypeInt32;
1054 1055 1056
    }
}

1057 1058 1059 1060 1061 1062 1063 1064 1065
void ParameterManager::_clearMetaData(void)
{
    if (_parameterMetaData) {
        _parameterMetaData->deleteLater();
        _parameterMetaData = NULL;
    }
}

void ParameterManager::_loadMetaData(void)
1066
{
1067 1068 1069
    if (_parameterMetaData) {
        return;
    }
1070

1071 1072
    QString metaDataFile;
    int majorVersion, minorVersion;
1073

1074 1075
    // Load best parameter meta data set
    metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
1076
    qCDebug(ParameterManagerLog) << "Loading meta data file:major:minor" << metaDataFile << majorVersion << minorVersion;
1077
    _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
1078 1079 1080 1081 1082 1083 1084 1085 1086 1087
}

void ParameterManager::_addMetaDataToDefaultComponent(void)
{
    _loadMetaData();

    if (_metaDataAddedToFacts) {
        return;
    }
    _metaDataAddedToFacts = true;
1088 1089

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

1096
void ParameterManager::_checkInitialLoadComplete(void)
1097 1098 1099 1100 1101
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1102

1103 1104 1105 1106 1107 1108
    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
1109

1110 1111 1112 1113 1114
    if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
        // No default component params yet, not done yet
        return;
    }

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

1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129
	// Parameter cache crc failure debugging
	foreach (int componentId, _debugCacheParamSeen.keys()) {
        if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
            foreach (const QString& paramName, _debugCacheParamSeen[componentId].keys()) {
                if (!_debugCacheParamSeen[componentId][paramName]) {
                    qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
                }
            }
        }
    }
    _debugCacheCRC.clear();

1130 1131
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";

1132 1133 1134 1135 1136 1137 1138 1139 1140 1141
    // 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;
1142
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1143 1144
        }
    }
1145 1146

    _missingParameters = false;
1147
    if (initialLoadFailures) {
1148
        _missingParameters = true;
1149 1150
        QString errorMsg = tr("%1 was unable to retrieve the full set of parameters from vehicle %2. "
                              "This will cause %1 to be unable to display its full user interface. "
1151
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1152
                              "If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(qgcApp()->applicationName()).arg(_vehicle->id());
1153 1154
        qCDebug(ParameterManagerLog) << errorMsg;
        qgcApp()->showMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
1155
        if (!qgcApp()->runningUnitTests()) {
1156
            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
1157
        }
1158 1159
    }

1160
    // Signal load complete
1161
    _parametersReady = true;
1162 1163 1164
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1165
}
1166

1167
void ParameterManager::_initialRequestTimeout(void)
1168
{
1169
    if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
1170
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retrying initial parameter request list";
1171 1172
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
1173 1174
    } else {
        if (!_vehicle->genericFirmware()) {
Don Gagne's avatar
Don Gagne committed
1175
            QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1176
                                  "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(qgcApp()->applicationName());
1177 1178 1179
            qCDebug(ParameterManagerLog) << errorMsg;
            qgcApp()->showMessage(errorMsg);
        }
1180
    }
1181
}
1182

1183
QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199
{
    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 {
1200
            qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232
            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 {
1233
                qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
1234 1235 1236 1237 1238 1239
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
1240
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile(vehicle);
1241
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
1242
    qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273
    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;
    }
1274
    qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
1275 1276 1277 1278

    return metaDataFile;
}

1279
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
1280 1281 1282 1283 1284
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
1285
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
1286 1287 1288

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
1289
    QString cacheHit = ParameterManager::parameterMetaDataFile(NULL, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
1290
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314

    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)));
1315
        qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
1316 1317 1318 1319
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1320 1321

/// Remap a parameter from one firmware version to another
1322
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333
{
    QString mappedParamName;

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

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

1334
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346

    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
1347
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1348 1349 1350 1351 1352
        return mappedParamName;
    }

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

1353
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1354 1355 1356 1357 1358 1359 1360

    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];
1361
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1362 1363 1364 1365 1366 1367 1368
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1369 1370

/// The offline editing vehicle can have custom loaded params bolted into it.
1371
void ParameterManager::_loadOfflineEditingParams(void)
1372 1373 1374 1375 1376 1377 1378 1379
{    
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1380
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394
    }

    QTextStream paramStream(&paramFile);

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

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

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

1395 1396
        int defaultComponentId = paramData.at(1).toInt();
        _vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
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
        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;
        }

1430 1431 1432 1433 1434
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1435 1436
        Fact* fact = new Fact(defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact);
1437 1438 1439
    }

    _addMetaDataToDefaultComponent();
1440
    _setupCategoryMap();
1441 1442
    _parametersReady = true;
    _initialLoadComplete = true;
1443
    _debugCacheCRC.clear();
1444
}
1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484

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;
1485
            Fact* fact = getParameter(compId, paramName);
1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543
            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;
        }

1544
        Fact* fact = getParameter(compId, name);
1545 1546 1547 1548 1549 1550
        fact->setRawValue(value);
    }

    return true;
}

1551 1552
void ParameterManager::resetAllParametersToDefaults(void)
{
1553 1554 1555 1556 1557
    _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
1558 1559
}

1560 1561 1562 1563 1564 1565 1566 1567
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);
    }
}
1568 1569 1570 1571 1572 1573

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