ParameterManager.cc 63.4 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 30 31 32 33
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";
34

35
ParameterManager::ParameterManager(Vehicle* vehicle)
36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55
    : 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)
56
{
57 58
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

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

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

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

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

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

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

79 80 81 82 83 84 85 86
    if (_vehicle->highLatencyLink()) {
        // High latency links don't load parameters
        _parametersReady = true;
        _missingParameters = true;
        _initialLoadComplete = true;
        _waitingForDefaultComponent = false;
        emit parametersReadyChanged(_parametersReady);
        emit missingParametersChanged(_missingParameters);
87
    } else if (!_logReplay){
88 89
        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 115
    // 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.
116
    if (parameterId == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
Patrick José Pereira's avatar
Patrick José Pereira committed
117
        qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to initial list response" << parameterName;
118 119 120
        return;
    }

121
    _initialRequestTimeoutTimer.stop();
dogmaphobic's avatar
dogmaphobic committed
122

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

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

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

149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
    // 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;
        }
    }

167
    _initialRequestTimeoutTimer.stop();
168
    _waitingParamTimeoutTimer.stop();
169

170
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
171

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

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

186 187 188
        // 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
189

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

193 194 195 196 197 198
    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;
    }

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

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

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

225 226 227
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
228

229
    for(int waitingComponentId: _waitingReadParamIndexMap.keys()) {
230 231 232
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
233
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
234 235
    }

236
    for(int waitingComponentId: _waitingReadParamNameMap.keys()) {
237 238 239
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
240
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
241
    }
dogmaphobic's avatar
dogmaphobic committed
242

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

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

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

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
331 332
    _dataMutex.unlock();

DonLakeFlyer's avatar
DonLakeFlyer committed
333 334 335 336 337 338 339 340 341
    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
342

343
    if (componentParamsComplete) {
344
        if (componentId == _vehicle->defaultComponentId()) {
345 346 347 348
            // Add meta data to default component. We need to do this before we setup the group map since group
            // map requires meta data.
            _addMetaDataToDefaultComponent();

349 350 351
            // 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.
Don Gagne's avatar
Don Gagne committed
352
            _setupDefaultComponentCategoryMap();
353
        }
354 355
    }

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

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

370
    _checkInitialLoadComplete();
371 372

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
373 374 375 376
}

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

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

389
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
390

DonLakeFlyer's avatar
DonLakeFlyer committed
391 392 393 394 395 396 397 398
    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
399

400
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
401

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

406
void ParameterManager::refreshAllParameters(uint8_t componentId)
407
{
Don Gagne's avatar
Don Gagne committed
408 409 410 411
    if (_logReplay) {
        return;
    }

412
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
413

414 415 416 417
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

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

429
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
430

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

433
    mavlink_message_t msg;
434 435 436 437 438
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,
                                             _vehicle->id(),
439
                                             componentId);
440
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
441

442
    QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
443
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
444 445 446
}

/// Translates FactSystem::defaultComponentId to real component id if needed
447
int ParameterManager::_actualComponentId(int componentId)
448 449
{
    if (componentId == FactSystem::defaultComponentId) {
450
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
451
        if (componentId == FactSystem::defaultComponentId) {
452
            qWarning() << _logVehiclePrefix(-1) << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
453
        }
454
    }
dogmaphobic's avatar
dogmaphobic committed
455

456 457 458
    return componentId;
}

459
void ParameterManager::refreshParameter(int componentId, const QString& name)
460
{
461
    componentId = _actualComponentId(componentId);
462
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
463

464 465 466
    _dataMutex.lock();

    if (_waitingReadParamNameMap.contains(componentId)) {
467 468 469 470
        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
471 472
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
473 474
    } else {
        qWarning() << "Internal error";
475
    }
dogmaphobic's avatar
dogmaphobic committed
476

477 478 479
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
480 481
}

482
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
483 484
{
    componentId = _actualComponentId(componentId);
485
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
486

487
    for(const QString &name: _mapParameterName2Variant[componentId].keys()) {
488 489 490 491 492 493
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

494
bool ParameterManager::parameterExists(int componentId, const QString&  name)
495
{
496
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
497

498 499
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
500
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
501
    }
502 503

    return ret;
504 505
}

506
Fact* ParameterManager::getParameter(int componentId, const QString& name)
507 508
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
509

510 511 512
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
513
        return &_defaultFact;
514
    }
dogmaphobic's avatar
dogmaphobic committed
515

516
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
517
}
518

519
QStringList ParameterManager::parameterNames(int componentId)
520
{
dogmaphobic's avatar
dogmaphobic committed
521 522
    QStringList names;

523
    for(const QString &paramName: _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
524 525 526 527
        names << paramName;
    }

    return names;
528 529
}

Don Gagne's avatar
Don Gagne committed
530
void ParameterManager::_setupDefaultComponentCategoryMap(void)
531
{
532
    // Must be able to handle being called multiple times
Don Gagne's avatar
Don Gagne committed
533
    _defaultComponentCategoryMap.clear();
534

535
    for (const QString &name: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
536
        Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value<Fact*>();
Don Gagne's avatar
Don Gagne committed
537
        _defaultComponentCategoryMap[fact->category()][fact->group()] += name;
538 539 540
    }
}

Don Gagne's avatar
Don Gagne committed
541
const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getDefaultComponentCategoryMap(void)
542
{
Don Gagne's avatar
Don Gagne committed
543
    return _defaultComponentCategoryMap;
544
}
545

546 547 548 549
/// 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)
550
{
551 552 553
    if (!_indexBatchQueueActive) {
        return false;
    }
dogmaphobic's avatar
dogmaphobic committed
554

555
    const int maxBatchSize = 10;
556

557 558 559 560 561 562 563
    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";
    }
564

565
    for(int componentId: _waitingReadParamIndexMap.keys()) {
566
        if (_waitingReadParamIndexMap[componentId].count()) {
567 568
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
569 570
        }

571
        for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
572 573 574 575 576 577 578
            if (_indexBatchQueue.contains(paramIndex)) {
                // Don't add more than once
                continue;
            }

            if (_indexBatchQueue.count() > maxBatchSize) {
                break;
579 580
            }

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

596 597 598 599 600
    return _indexBatchQueue.count() != 0;
}

void ParameterManager::_waitingParamTimeout(void)
{
601 602 603 604
    if (_logReplay) {
        return;
    }

605 606 607 608
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;

609
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
610 611 612 613 614 615 616

    // 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 */);

617 618 619
    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.
620
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
621 622 623 624 625 626
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

627
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
628

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

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

673 674
Out:
    if (paramsRequested) {
675
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
676 677 678 679
        _waitingParamTimeoutTimer.start();
    }
}

680
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
681 682 683 684 685
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
686 687 688 689 690 691 692 693
    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
694
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
695 696
}

697
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
698 699 700
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
701

Don Gagne's avatar
Don Gagne committed
702 703
    memset(&p, 0, sizeof(p));

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

707
    switch (factType) {
708 709 710
    case FactMetaData::valueTypeUint8:
        union_value.param_uint8 = (uint8_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
711

712 713 714
    case FactMetaData::valueTypeInt8:
        union_value.param_int8 = (int8_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
715

716 717 718
    case FactMetaData::valueTypeUint16:
        union_value.param_uint16 = (uint16_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
719

720 721 722
    case FactMetaData::valueTypeInt16:
        union_value.param_int16 = (int16_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
723

724 725 726
    case FactMetaData::valueTypeUint32:
        union_value.param_uint32 = (uint32_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
727

728 729 730
    case FactMetaData::valueTypeFloat:
        union_value.param_float = value.toFloat();
        break;
dogmaphobic's avatar
dogmaphobic committed
731

732 733 734
    default:
        qCritical() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
735

736 737 738
    case FactMetaData::valueTypeInt32:
        union_value.param_int32 = (int32_t)value.toInt();
        break;
739
    }
dogmaphobic's avatar
dogmaphobic committed
740

741
    p.param_value = union_value.param_float;
742
    p.target_system = (uint8_t)_vehicle->id();
743
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
744

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

747
    mavlink_message_t msg;
748 749 750 751 752
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      &p);
753
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
754 755
}

756
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
757
{
758
    CacheMapName2ParamTypeVal cacheMap;
759

760
    for(const QString& name: _mapParameterName2Variant[componentId].keys()) {
761
        const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
762
        cacheMap[name] = ParamTypeVal(fact->type(), fact->rawValue());
763 764
    }

765 766
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
767

768 769
    QDataStream ds(&cacheFile);
    ds << cacheMap;
770 771
}

772
QDir ParameterManager::parameterCacheDir()
773 774 775 776 777
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

778
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
779
{
780
    return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
781 782
}

783
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
784
{
785 786
    qCInfo(ParameterManagerLog) << "Attemping load from cache";

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

    /* Deserialize the parameter cache table */
798 799 800 801 802 803 804 805 806
    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();
807 808

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

810
    FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin();
811
    for (const QString& name: cacheMap.keys()) {
812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828
        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);
        }
829 830
    }

831
    /* if the two param set hashes match, just load from the disk */
832
    if (crc32_value == hash_value.toUInt()) {
833 834 835 836
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());

        int count = cacheMap.count();
        int index = 0;
837
        for (const QString& name: cacheMap.keys()) {
838 839
            const ParamTypeVal& paramTypeVal = cacheMap[name];
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
840
            const int mavType = _factTypeToMavType(fact_type);
841
            _parameterUpdate(vehicleId, componentId, name, count, index++, mavType, paramTypeVal.second);
842
        }
843

844 845 846
        // 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
847
        memset(&p, 0, sizeof(p));
848 849 850 851 852 853 854
        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;
855 856 857 858 859
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
                                          _vehicle->priorityLink()->mavlinkChannel(),
                                          &msg,
                                          &p);
860
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
861 862 863 864 865 866 867 868

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

869
        connect(ani, &QVariantAnimation::valueChanged, this, [this](const QVariant &value) {
870
            _setLoadProgress(value.toDouble());
871 872 873
        });

        // Hide 500ms after animation finishes
874 875
        connect(ani, &QVariantAnimation::finished, this, [this] {
            QTimer::singleShot(500, [this] {
876
                _setLoadProgress(0);
877 878 879 880
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
DonLakeFlyer's avatar
DonLakeFlyer committed
881
    } else {
882 883 884 885
        // 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());
886 887 888
        if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
            _debugCacheCRC[componentId] = true;
            _debugCacheMap[componentId] = cacheMap;
889
            for (const QString& name: cacheMap.keys()) {
890 891 892
                _debugCacheParamSeen[componentId][name] = false;
            }
            qgcApp()->showMessage(tr("Parameter cache CRC match failed"));
893
        }
Don Gagne's avatar
Don Gagne committed
894
    }
895 896
}

897
QString ParameterManager::readParametersFromStream(QTextStream& stream)
898
{
899
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
900

901 902 903 904 905 906
    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
907 908
                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
909 910
                }

911 912 913 914
                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
915

916
                if (!parameterExists(componentId, paramName)) {
917 918 919
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
920
                    qCDebug(ParameterManagerLog) << error;
921 922
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
923

924
                Fact* fact = getParameter(componentId, paramName);
925
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
926 927 928
                    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;
929
                    qCDebug(ParameterManagerLog) << error;
930 931
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
932

933
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
934
                fact->setRawValue(valStr);
935 936 937
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
938

939
    return errors;
940 941
}

942
void ParameterManager::writeParametersToStream(QTextStream &stream)
943
{
Don Gagne's avatar
Don Gagne committed
944
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
945 946 947 948 949 950 951 952 953 954 955
    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";

956
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
957
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
958

959 960
    for (int componentId: _mapParameterName2Variant.keys()) {
        for (const QString &paramName: _mapParameterName2Variant[componentId].keys()) {
961
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
962 963 964 965 966
            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";
            }
967 968
        }
    }
dogmaphobic's avatar
dogmaphobic committed
969

970 971 972
    stream.flush();
}

973
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
974 975
{
    switch (factType) {
976 977
    case FactMetaData::valueTypeUint8:
        return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
978

979 980
    case FactMetaData::valueTypeInt8:
        return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
981

982 983
    case FactMetaData::valueTypeUint16:
        return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
984

985 986
    case FactMetaData::valueTypeInt16:
        return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
987

988 989
    case FactMetaData::valueTypeUint32:
        return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
990

991 992 993 994 995 996
    case FactMetaData::valueTypeUint64:
        return MAV_PARAM_TYPE_UINT64;

    case FactMetaData::valueTypeInt64:
        return MAV_PARAM_TYPE_INT64;

997 998
    case FactMetaData::valueTypeFloat:
        return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
999

1000 1001 1002
    case FactMetaData::valueTypeDouble:
        return MAV_PARAM_TYPE_REAL64;

1003 1004 1005
    default:
        qWarning() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1006

1007 1008
    case FactMetaData::valueTypeInt32:
        return MAV_PARAM_TYPE_INT32;
1009 1010 1011
    }
}

1012
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
1013 1014
{
    switch (mavType) {
1015 1016
    case MAV_PARAM_TYPE_UINT8:
        return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
1017

1018 1019
    case MAV_PARAM_TYPE_INT8:
        return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
1020

1021 1022
    case MAV_PARAM_TYPE_UINT16:
        return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
1023

1024 1025
    case MAV_PARAM_TYPE_INT16:
        return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
1026

1027 1028
    case MAV_PARAM_TYPE_UINT32:
        return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
1029

1030 1031 1032 1033 1034 1035
    case MAV_PARAM_TYPE_UINT64:
        return FactMetaData::valueTypeUint64;

    case MAV_PARAM_TYPE_INT64:
        return FactMetaData::valueTypeInt64;

1036 1037
    case MAV_PARAM_TYPE_REAL32:
        return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
1038

1039 1040 1041
    case MAV_PARAM_TYPE_REAL64:
        return FactMetaData::valueTypeDouble;

1042 1043 1044
    default:
        qWarning() << "Unsupported mav param type" << mavType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1045

1046 1047
    case MAV_PARAM_TYPE_INT32:
        return FactMetaData::valueTypeInt32;
1048 1049 1050
    }
}

1051 1052 1053 1054 1055 1056 1057 1058 1059
void ParameterManager::_clearMetaData(void)
{
    if (_parameterMetaData) {
        _parameterMetaData->deleteLater();
        _parameterMetaData = NULL;
    }
}

void ParameterManager::_loadMetaData(void)
1060
{
1061 1062 1063
    if (_parameterMetaData) {
        return;
    }
1064

1065 1066
    QString metaDataFile;
    int majorVersion, minorVersion;
1067

1068 1069
    // Load best parameter meta data set
    metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
1070
    qCDebug(ParameterManagerLog) << "Loading meta data file:major:minor" << metaDataFile << majorVersion << minorVersion;
1071
    _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
1072 1073 1074 1075 1076 1077 1078 1079 1080 1081
}

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

    if (_metaDataAddedToFacts) {
        return;
    }
    _metaDataAddedToFacts = true;
1082 1083

    // Loop over all parameters in default component adding meta data
1084
    QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()];
1085
    for (const QString& key: factMap.keys()) {
1086 1087 1088 1089
        _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value<Fact*>(), _vehicle->vehicleType());
    }
}

1090
void ParameterManager::_checkInitialLoadComplete(void)
1091 1092 1093 1094 1095
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1096

1097
    for (int componentId: _waitingReadParamIndexMap.keys()) {
1098 1099 1100 1101 1102
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1103

1104 1105 1106 1107 1108
    if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
        // No default component params yet, not done yet
        return;
    }

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

1112 1113
    // Parameter cache crc failure debugging
    for (int componentId: _debugCacheParamSeen.keys()) {
1114
        if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
1115
            for (const QString& paramName: _debugCacheParamSeen[componentId].keys()) {
1116 1117 1118 1119 1120 1121 1122 1123
                if (!_debugCacheParamSeen[componentId][paramName]) {
                    qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
                }
            }
        }
    }
    _debugCacheCRC.clear();

1124
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Initial load complete";
1125

1126 1127 1128
    // Check for index based load failures
    QString indexList;
    bool initialLoadFailures = false;
1129 1130
    for (int componentId: _failedReadParamIndexMap.keys()) {
        for (int paramIndex: _failedReadParamIndexMap[componentId]) {
1131 1132 1133
            if (initialLoadFailures) {
                indexList += ", ";
            }
1134
            indexList += QString("%1:%2").arg(componentId).arg(paramIndex);
1135
            initialLoadFailures = true;
1136
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1137 1138
        }
    }
1139 1140

    _missingParameters = false;
1141
    if (initialLoadFailures) {
1142
        _missingParameters = true;
1143 1144
        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. "
1145
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1146
                              "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());
1147 1148
        qCDebug(ParameterManagerLog) << errorMsg;
        qgcApp()->showMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
1149
        if (!qgcApp()->runningUnitTests()) {
1150
            qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
Don Gagne's avatar
Don Gagne committed
1151
        }
1152 1153
    }

1154
    // Signal load complete
1155
    _parametersReady = true;
1156 1157 1158
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1159
}
1160

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

1177
QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193
{
    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 {
1194
            qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
1195 1196 1197 1198 1199 1200 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
            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 {
1227
                qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
1228 1229 1230 1231 1232 1233
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
1234
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile(vehicle);
1235
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
1236
    qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
1237 1238 1239 1240 1241 1242 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
    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;
    }
1268
    qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
1269 1270 1271 1272

    return metaDataFile;
}

1273
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
1274 1275 1276 1277 1278
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
1279
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
1280 1281 1282

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

    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)));
1309
        qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
1310 1311 1312 1313
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1314 1315

/// Remap a parameter from one firmware version to another
1316
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327
{
    QString mappedParamName;

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

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

1328
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340

    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
1341
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1342 1343 1344 1345 1346
        return mappedParamName;
    }

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

1347
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1348 1349 1350 1351 1352 1353 1354

    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];
1355
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1356 1357 1358 1359 1360 1361 1362
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1363 1364

/// The offline editing vehicle can have custom loaded params bolted into it.
1365
void ParameterManager::_loadOfflineEditingParams(void)
1366
{
1367 1368 1369 1370 1371 1372 1373
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1374
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388
    }

    QTextStream paramStream(&paramFile);

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

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

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

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

1424 1425 1426 1427 1428
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1429 1430
        Fact* fact = new Fact(defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact);
1431 1432 1433
    }

    _addMetaDataToDefaultComponent();
Don Gagne's avatar
Don Gagne committed
1434
    _setupDefaultComponentCategoryMap();
1435 1436
    _parametersReady = true;
    _initialLoadComplete = true;
1437
    _debugCacheCRC.clear();
1438
}
1439 1440 1441 1442 1443 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

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;
1479
            Fact* fact = getParameter(compId, paramName);
1480 1481 1482 1483 1484 1485 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
            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;
        }

1538
        Fact* fact = getParameter(compId, name);
1539 1540 1541 1542 1543 1544
        fact->setRawValue(value);
    }

    return true;
}

1545
void ParameterManager::resetAllParametersToDefaults()
1546
{
1547 1548 1549 1550 1551
    _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
1552 1553
}

1554 1555 1556 1557 1558 1559 1560 1561 1562
void ParameterManager::resetAllToVehicleConfiguration()
{
    //-- https://github.com/PX4/Firmware/pull/11760
    Fact* sysAutoConfigFact = getParameter(-1, "SYS_AUTOCONFIG");
    if(sysAutoConfigFact) {
        sysAutoConfigFact->setRawValue(2);
    }
}

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

void ParameterManager::_setLoadProgress(double loadProgress)
{
    _loadProgress = loadProgress;
1575
    emit loadProgressChanged(static_cast<float>(loadProgress));
1576
}
Don Gagne's avatar
Don Gagne committed
1577 1578 1579 1580 1581

QList<int> ParameterManager::componentIds(void)
{
    return _paramCountMap.keys();
}