ParameterManager.cc 57.8 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * 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 "ComponentInformationManager.h"
#include "CompInfoParam.h"
20

21
#include <QEasingCurve>
22 23
#include <QFile>
#include <QDebug>
24
#include <QVariantAnimation>
25
#include <QJsonArray>
26

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

31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55
const QHash<int, QString> _mavlinkCompIdHash {
    { MAV_COMP_ID_CAMERA,   "Camera1" },
    { MAV_COMP_ID_CAMERA2,  "Camera2" },
    { MAV_COMP_ID_CAMERA3,  "Camera3" },
    { MAV_COMP_ID_CAMERA4,  "Camera4" },
    { MAV_COMP_ID_CAMERA5,  "Camera5" },
    { MAV_COMP_ID_CAMERA6,  "Camera6" },
    { MAV_COMP_ID_SERVO1,   "Servo1" },
    { MAV_COMP_ID_SERVO2,   "Servo2" },
    { MAV_COMP_ID_SERVO3,   "Servo3" },
    { MAV_COMP_ID_SERVO4,   "Servo4" },
    { MAV_COMP_ID_SERVO5,   "Servo5" },
    { MAV_COMP_ID_SERVO6,   "Servo6" },
    { MAV_COMP_ID_SERVO7,   "Servo7" },
    { MAV_COMP_ID_SERVO8,   "Servo8" },
    { MAV_COMP_ID_SERVO9,   "Servo9" },
    { MAV_COMP_ID_SERVO10,  "Servo10" },
    { MAV_COMP_ID_SERVO11,  "Servo11" },
    { MAV_COMP_ID_SERVO12,  "Servo12" },
    { MAV_COMP_ID_SERVO13,  "Servo13" },
    { MAV_COMP_ID_SERVO14,  "Servo14" },
    { MAV_COMP_ID_GIMBAL,   "Gimbal1" },
    { MAV_COMP_ID_ADSB,     "ADSB" },
    { MAV_COMP_ID_OSD,      "OSD" },
    { MAV_COMP_ID_FLARM,    "FLARM" },
56 57 58 59 60
    { MAV_COMP_ID_GIMBAL2,  "Gimbal2" },
    { MAV_COMP_ID_GIMBAL3,  "Gimbal3" },
    { MAV_COMP_ID_GIMBAL4,  "Gimbal4" },
    { MAV_COMP_ID_GIMBAL5,  "Gimbal5" },
    { MAV_COMP_ID_GIMBAL6,  "Gimbal6" },
61 62 63 64 65 66 67
    { MAV_COMP_ID_IMU,      "IMU1" },
    { MAV_COMP_ID_IMU_2,    "IMU2" },
    { MAV_COMP_ID_IMU_3,    "IMU3" },
    { MAV_COMP_ID_GPS,      "GPS1" },
    { MAV_COMP_ID_GPS2,     "GPS2" }
};

68 69 70 71
const char* ParameterManager::_jsonParametersKey =          "parameters";
const char* ParameterManager::_jsonCompIdKey =              "compId";
const char* ParameterManager::_jsonParamNameKey =           "name";
const char* ParameterManager::_jsonParamValueKey =          "value";
72

73
ParameterManager::ParameterManager(Vehicle* vehicle)
74 75
    : QObject                           (vehicle)
    , _vehicle                          (vehicle)
76
    , _mavlink                          (nullptr)
77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92
    , _loadProgress                     (0.0)
    , _parametersReady                  (false)
    , _missingParameters                (false)
    , _initialLoadComplete              (false)
    , _waitingForDefaultComponent       (false)
    , _saveRequired                     (false)
    , _metaDataAddedToFacts             (false)
    , _logReplay                        (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay())
    , _parameterSetMajorVersion         (-1)
    , _prevWaitingReadParamIndexCount   (0)
    , _prevWaitingReadParamNameCount    (0)
    , _prevWaitingWriteParamNameCount   (0)
    , _initialRequestRetryCount         (0)
    , _disableAllRetries                (false)
    , _indexBatchQueueActive            (false)
    , _totalParamCount                  (0)
93
{
94 95
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

96 97 98 99 100 101
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

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

103
    _initialRequestTimeoutTimer.setSingleShot(true);
104
    _initialRequestTimeoutTimer.setInterval(5000);
105
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
106

107
    _waitingParamTimeoutTimer.setSingleShot(true);
108
    _waitingParamTimeoutTimer.setInterval(3000);
109
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
110

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

113 114
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
115 116
}

117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173
void ParameterManager::_updateProgressBar(void)
{
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamCount = 0;

    for (int compId: _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[compId].count();
    }
    for(int compId: _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[compId].count();
    }
    for(int compId: _waitingWriteParamNameMap.keys()) {
        waitingWriteParamCount += _waitingWriteParamNameMap[compId].count();
    }

    if (waitingReadParamIndexCount == 0) {
        if (_readParamIndexProgressActive) {
            _readParamIndexProgressActive = false;
            _setLoadProgress(0.0);
            return;
        }
    } else {
        _readParamIndexProgressActive = true;
        _setLoadProgress((double)(_totalParamCount - waitingReadParamIndexCount) / (double)_totalParamCount);
        return;
    }

    if (waitingWriteParamCount == 0) {
        if (_writeParamProgressActive) {
            _writeParamProgressActive = false;
            _waitingWriteParamBatchCount = 0;
            _setLoadProgress(0.0);
            emit pendingWritesChanged(false);
            return;
        }
    } else {
        _writeParamProgressActive = true;
        _setLoadProgress((double)(qMax(_waitingWriteParamBatchCount - waitingWriteParamCount, 1)) / (double)(_waitingWriteParamBatchCount + 1));
        emit pendingWritesChanged(true);
        return;
    }

    if (waitingReadParamNameCount == 0) {
        if (_readParamNameProgressActive) {
            _readParamNameProgressActive = false;
            _waitingReadParamNameBatchCount = 0;
            _setLoadProgress(0.0);
            return;
        }
    } else {
        _readParamNameProgressActive = true;
        _setLoadProgress((double)(qMax(_waitingReadParamNameBatchCount - waitingReadParamNameCount, 1)) / (double)(_waitingReadParamNameBatchCount + 1));
        return;
    }
}

174
/// Called whenever a parameter is updated or first seen.
175
void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
176 177
{
    // Is this for our uas?
178
    if (vehicleId != _vehicle->id()) {
179 180
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
181

182 183 184 185 186 187 188 189
    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
                                            "_parameterUpdate" <<
                                            "name:" << parameterName <<
                                            "count:" << parameterCount <<
                                            "index:" << parameterId <<
                                            "mavType:" << mavType <<
                                            "value:" << value <<
                                            ")";
190

191 192
    // 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.
193
    if (parameterId == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
Patrick José Pereira's avatar
Patrick José Pereira committed
194
        qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to initial list response" << parameterName;
195 196 197
        return;
    }

198
    _initialRequestTimeoutTimer.stop();
dogmaphobic's avatar
dogmaphobic committed
199

200
#if 0
201 202 203 204 205 206 207
    if (!_initialLoadComplete && !_indexBatchQueueActive) {
        // Handy for testing retry logic
        static int counter = 0;
        if (counter++ & 0x8) {
            qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
            return;
        }
208 209
    }
#endif
210

211 212 213 214 215 216 217
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

218 219 220 221 222 223
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
        if (!_initialLoadComplete && !_logReplay) {
            /* we received a cache hash, potentially load from cache */
            _tryCacheHashLoad(vehicleId, componentId, value);
        }
        return;
224
    }
225

226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243
    // 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;
        }
    }

244
    _initialRequestTimeoutTimer.stop();
245
    _waitingParamTimeoutTimer.stop();
246

247
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
248

249 250 251 252 253
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
254

255 256
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
257 258 259 260
        // 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;
261
        }
dogmaphobic's avatar
dogmaphobic committed
262

263 264 265
        // 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
266

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

270 271 272 273 274 275
    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;
    }

276
    if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
277 278
            !_waitingReadParamNameMap[componentId].contains(parameterName) &&
            !_waitingWriteParamNameMap[componentId].contains(parameterName)) {
279
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Unrequested param update" << parameterName;
280 281
    }

282
    // Remove this parameter from the waiting lists
283 284 285 286 287
    if (_waitingReadParamIndexMap[componentId].contains(parameterId)) {
        _waitingReadParamIndexMap[componentId].remove(parameterId);
        _indexBatchQueue.removeOne(parameterId);
        _fillIndexBatchQueue(false /* waitingParamTimeout */);
    }
288 289
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
290 291 292 293 294 295 296 297 298
    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];
    }
299 300

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

302 303 304
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
305

306
    for(int waitingComponentId: _waitingReadParamIndexMap.keys()) {
307 308 309
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
310
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
311 312
    }

313
    for(int waitingComponentId: _waitingReadParamNameMap.keys()) {
314 315 316
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
317
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
318
    }
dogmaphobic's avatar
dogmaphobic committed
319

320
    for(int waitingComponentId: _waitingWriteParamNameMap.keys()) {
321 322 323
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
324
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
325
    }
dogmaphobic's avatar
dogmaphobic committed
326

Don Gagne's avatar
Don Gagne committed
327 328 329
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
330 331
        // More params to wait for, restart timer
        _waitingParamTimeoutTimer.start();
332
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
333
    } else {
334 335
        if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
            // Still waiting for parameters from default component
336
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
337 338
            _waitingParamTimeoutTimer.start();
        } else {
339
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
340
        }
341
    }
342 343
\
    _updateProgressBar();
dogmaphobic's avatar
dogmaphobic committed
344

345 346 347 348 349
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

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

353 354
        FactMetaData::ValueType_t factType;
        switch (mavType) {
355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372
        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;
373 374 375 376 377 378
        case MAV_PARAM_TYPE_UINT64:
            factType = FactMetaData::valueTypeUint64;
            break;
        case MAV_PARAM_TYPE_INT64:
            factType = FactMetaData::valueTypeInt64;
            break;
379 380 381 382 383 384 385 386 387 388
        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;
389
        }
dogmaphobic's avatar
dogmaphobic committed
390

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

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

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

Don Gagne's avatar
Don Gagne committed
399 400
    _dataMutex.unlock();

401
    Fact* fact = nullptr;
DonLakeFlyer's avatar
DonLakeFlyer committed
402 403 404 405 406 407 408 409
    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
410

411
    if (componentParamsComplete) {
412
        if (componentId == _vehicle->defaultComponentId()) {
413 414 415
            // Add meta data to default component. We need to do this before we setup the group map since group
            // map requires meta data.
            _addMetaDataToDefaultComponent();
416
        }
417 418 419 420
        // 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.
        _setupComponentCategoryMap(componentId);
421 422
    }

Don Gagne's avatar
Don Gagne committed
423 424 425
    // 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.
426
    if (!_logReplay && _vehicle->px4Firmware()) {
Don Gagne's avatar
Don Gagne committed
427 428
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
            // All reads just finished, update the cache
429
            _writeLocalParamCache(vehicleId, componentId);
Don Gagne's avatar
Don Gagne committed
430 431 432 433 434 435 436
        }
    }

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

437
    _checkInitialLoadComplete();
438 439

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
440 441 442 443
}

/// Connected to Fact::valueUpdated
///
444
/// Writes the parameter to mavlink, sets up for write wait
445
void ParameterManager::_valueUpdated(const QVariant& value)
446 447
{
    Fact* fact = qobject_cast<Fact*>(sender());
DonLakeFlyer's avatar
DonLakeFlyer committed
448 449 450 451
    if (!fact) {
        qWarning() << "Internal error";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
452

453
    int componentId = fact->componentId();
454
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
455

456
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
457

DonLakeFlyer's avatar
DonLakeFlyer committed
458
    if (_waitingWriteParamNameMap.contains(componentId)) {
459 460 461 462 463 464 465
        if (_waitingWriteParamNameMap[componentId].contains(name)) {
            _waitingWriteParamNameMap[componentId].remove(name);
        } else {
            _waitingWriteParamBatchCount++;
        }
        _waitingWriteParamNameMap[componentId][name] = 0; // Add new entry and set retry count
        _updateProgressBar();
DonLakeFlyer's avatar
DonLakeFlyer committed
466 467 468 469 470
        _waitingParamTimeoutTimer.start();
        _saveRequired = true;
    } else {
        qWarning() << "Internal error";
    }
dogmaphobic's avatar
dogmaphobic committed
471

472
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
473

474
    _writeParameterRaw(componentId, fact->name(), value);
475
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
476 477
}

478
void ParameterManager::refreshAllParameters(uint8_t componentId)
479
{
480 481 482 483 484 485 486 487
    if (_vehicle->highLatencyLink() || _logReplay) {
        // These links don't load params
        _parametersReady = true;
        _missingParameters = true;
        _initialLoadComplete = true;
        _waitingForDefaultComponent = false;
        emit parametersReadyChanged(_parametersReady);
        emit missingParametersChanged(_missingParameters);
Don Gagne's avatar
Don Gagne committed
488 489
    }

490
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
491

492 493 494 495
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

496
    // Reset index wait lists
497
    for (int cid: _paramCountMap.keys()) {
498
        // Add/Update all indices to the wait list, parameter index is 0-based
499
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
500 501
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
502
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
503
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
504 505
        }
    }
dogmaphobic's avatar
dogmaphobic committed
506

507
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
508

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

511
    mavlink_message_t msg;
512 513 514 515 516
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,
                                             _vehicle->id(),
517
                                             componentId);
518
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
519

520
    QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
521
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
522 523 524
}

/// Translates FactSystem::defaultComponentId to real component id if needed
525
int ParameterManager::_actualComponentId(int componentId)
526 527
{
    if (componentId == FactSystem::defaultComponentId) {
528
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
529
        if (componentId == FactSystem::defaultComponentId) {
530
            qWarning() << _logVehiclePrefix(-1) << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
531
        }
532
    }
dogmaphobic's avatar
dogmaphobic committed
533

534 535 536
    return componentId;
}

537
void ParameterManager::refreshParameter(int componentId, const QString& paramName)
538
{
539
    componentId = _actualComponentId(componentId);
540
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
dogmaphobic's avatar
dogmaphobic committed
541

542 543 544
    _dataMutex.lock();

    if (_waitingReadParamNameMap.contains(componentId)) {
545
        QString mappedParamName = _remapParamNameToVersion(paramName);
546

547 548 549 550 551
        if (_waitingReadParamNameMap[componentId].contains(mappedParamName)) {
            _waitingReadParamNameMap[componentId].remove(mappedParamName);
        } else {
            _waitingReadParamNameBatchCount++;
        }
552
        _waitingReadParamNameMap[componentId][mappedParamName] = 0;     // Add new wait entry and update retry count
553
        _updateProgressBar();
554 555
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
556 557
    } else {
        qWarning() << "Internal error";
558
    }
dogmaphobic's avatar
dogmaphobic committed
559

560 561
    _dataMutex.unlock();

562
    _readParameterRaw(componentId, paramName, -1);
563 564
}

565
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
566 567
{
    componentId = _actualComponentId(componentId);
568
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
569

570 571 572
    for(const QString &paramName: _mapParameterName2Variant[componentId].keys()) {
        if (paramName.startsWith(namePrefix)) {
            refreshParameter(componentId, paramName);
573 574 575 576
        }
    }
}

577
bool ParameterManager::parameterExists(int componentId, const QString& paramName)
578
{
579
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
580

581 582
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
583
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(paramName));
584
    }
585 586

    return ret;
587 588
}

589
Fact* ParameterManager::getParameter(int componentId, const QString& paramName)
590 591
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
592

593
    QString mappedParamName = _remapParamNameToVersion(paramName);
594 595
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
596
        return &_defaultFact;
597
    }
dogmaphobic's avatar
dogmaphobic committed
598

599
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
600
}
601

602
QStringList ParameterManager::parameterNames(int componentId)
603
{
dogmaphobic's avatar
dogmaphobic committed
604 605
    QStringList names;

606
    for(const QString &paramName: _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
607 608 609 610
        names << paramName;
    }

    return names;
611 612
}

613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632
void ParameterManager::_setupComponentCategoryMap(int componentId)
{
    if (componentId == _vehicle->defaultComponentId()) {
        _setupDefaultComponentCategoryMap();
        return;
    }

    ComponentCategoryMapType& componentCategoryMap = _componentCategoryMaps[componentId];

    QString category = getComponentCategory(componentId);

    // Must be able to handle being called multiple times
    componentCategoryMap.clear();

    // Fill parameters into the group determined by param name
    for (const QString &paramName: _mapParameterName2Variant[componentId].keys()) {
        int i = paramName.indexOf("_");
        if (i > 0) {
            componentCategoryMap[category][paramName.left(i)] += paramName;
        } else {
633
            componentCategoryMap[category][tr("Misc")] += paramName;
634 635 636 637 638 639 640 641 642
        }
    }

    // Memorize category for component ID
    if (!_componentCategoryHash.contains(category)) {
        _componentCategoryHash.insert(category, componentId);
    }
}

Don Gagne's avatar
Don Gagne committed
643
void ParameterManager::_setupDefaultComponentCategoryMap(void)
644
{
645 646
    ComponentCategoryMapType& defaultComponentCategoryMap = _componentCategoryMaps[_vehicle->defaultComponentId()];

647
    // Must be able to handle being called multiple times
648 649 650 651 652 653 654
    defaultComponentCategoryMap.clear();

    for (const QString &paramName: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) {
        Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][paramName].value<Fact*>();
        defaultComponentCategoryMap[fact->category()][fact->group()] += paramName;
    }
}
655

656 657 658
QString ParameterManager::getComponentCategory(int componentId)
{
    if (_mavlinkCompIdHash.contains(componentId)) {
659
        return tr("Component %1  (%2)").arg(_mavlinkCompIdHash.value(componentId)).arg(componentId);
660
    }
661 662 663 664 665 666 667
    QString componentCategoryPrefix = tr("Component ");
    return QString("%1%2").arg(componentCategoryPrefix).arg(componentId);
}

const QMap<QString, QMap<QString, QStringList> >& ParameterManager::getComponentCategoryMap(int componentId)
{
    return _componentCategoryMaps[componentId];
668 669
}

670
int  ParameterManager::getComponentId(const QString& category)
671
{
672
    return (_componentCategoryHash.contains(category)) ? _componentCategoryHash.value(category) : _vehicle->defaultComponentId();
673
}
674

675 676 677 678
/// 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)
679
{
680 681 682
    if (!_indexBatchQueueActive) {
        return false;
    }
dogmaphobic's avatar
dogmaphobic committed
683

684
    const int maxBatchSize = 10;
685

686 687 688 689 690 691 692
    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";
    }
693

694
    for(int componentId: _waitingReadParamIndexMap.keys()) {
695
        if (_waitingReadParamIndexMap[componentId].count()) {
696 697
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
698 699
        }

700
        for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
701 702 703 704 705 706 707
            if (_indexBatchQueue.contains(paramIndex)) {
                // Don't add more than once
                continue;
            }

            if (_indexBatchQueue.count() > maxBatchSize) {
                break;
708 709
            }

710
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
711
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
712 713
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
714
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
715 716 717
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
718
                _indexBatchQueue.append(paramIndex);
719
                _readParameterRaw(componentId, "", paramIndex);
720
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
721 722 723
            }
        }
    }
724

725 726 727 728 729
    return _indexBatchQueue.count() != 0;
}

void ParameterManager::_waitingParamTimeout(void)
{
730 731 732 733
    if (_logReplay) {
        return;
    }

734 735 736 737
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;

738
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
739 740 741 742 743 744 745

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

746 747 748
    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.
749
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
750 751 752 753 754 755
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

756
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
757

758
    if (!paramsRequested) {
759 760
        for(int componentId: _waitingWriteParamNameMap.keys()) {
            for(const QString &paramName: _waitingWriteParamNameMap[componentId].keys()) {
761
                paramsRequested = true;
762
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
763
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
764
                    _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
765
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
766
                    if (++batchCount > maxBatchSize) {
767 768 769 770 771
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
772 773
                    QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
774
                    qgcApp()->showAppMessage(errorMsg);
775 776 777 778
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
779

780
    if (!paramsRequested) {
781 782
        for(int componentId: _waitingReadParamNameMap.keys()) {
            for(const QString &paramName: _waitingReadParamNameMap[componentId].keys()) {
783
                paramsRequested = true;
784
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
785 786
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
787
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
788
                    if (++batchCount > maxBatchSize) {
789 790 791 792 793
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
794 795
                    QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
796
                    qgcApp()->showAppMessage(errorMsg);
797 798 799 800
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
801

802 803
Out:
    if (paramsRequested) {
804
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
805 806 807 808
        _waitingParamTimeoutTimer.start();
    }
}

809
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
810 811 812 813 814
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
815 816 817 818 819 820 821 822
    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
823
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->priorityLink(), msg);
824 825
}

826
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
827 828 829
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
830

Don Gagne's avatar
Don Gagne committed
831 832
    memset(&p, 0, sizeof(p));

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

836
    switch (factType) {
837 838 839
    case FactMetaData::valueTypeUint8:
        union_value.param_uint8 = (uint8_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
840

841 842 843
    case FactMetaData::valueTypeInt8:
        union_value.param_int8 = (int8_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
844

845 846 847
    case FactMetaData::valueTypeUint16:
        union_value.param_uint16 = (uint16_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
848

849 850 851
    case FactMetaData::valueTypeInt16:
        union_value.param_int16 = (int16_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
852

853 854 855
    case FactMetaData::valueTypeUint32:
        union_value.param_uint32 = (uint32_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
856

857 858 859
    case FactMetaData::valueTypeFloat:
        union_value.param_float = value.toFloat();
        break;
dogmaphobic's avatar
dogmaphobic committed
860

861 862 863
    default:
        qCritical() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
864

865 866 867
    case FactMetaData::valueTypeInt32:
        union_value.param_int32 = (int32_t)value.toInt();
        break;
868
    }
dogmaphobic's avatar
dogmaphobic committed
869

870
    p.param_value = union_value.param_float;
871
    p.target_system = (uint8_t)_vehicle->id();
872
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
873

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

876
    mavlink_message_t msg;
877 878 879 880 881
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      &p);
882
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->priorityLink(), msg);
883 884
}

885
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
886
{
887
    CacheMapName2ParamTypeVal cacheMap;
888

889 890 891
    for(const QString& paramName: _mapParameterName2Variant[componentId].keys()) {
        const Fact *fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
        cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
892 893
    }

894 895
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
896

897 898
    QDataStream ds(&cacheFile);
    ds << cacheMap;
899 900
}

901
QDir ParameterManager::parameterCacheDir()
902 903 904 905 906
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

907
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
908
{
909
    return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
910 911
}

912
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
913
{
914 915
    qCInfo(ParameterManagerLog) << "Attemping load from cache";

916 917
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
918 919 920
    CacheMapName2ParamTypeVal cacheMap;
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    if (!cacheFile.exists()) {
921
        /* no local cache, just wait for them to come in*/
922 923
        return;
    }
924
    cacheFile.open(QIODevice::ReadOnly);
925 926

    /* Deserialize the parameter cache table */
927 928 929 930 931 932 933 934
    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();
    }
935
    _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_parameterMajorVersionKnown(_parameterSetMajorVersion);
936 937

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

939
    for (const QString& name: cacheMap.keys()) {
940
        if (_vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_isParameterVolatile(name)) {
941 942 943 944 945 946 947 948 949
            // 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);
        }
950 951
    }

952
    /* if the two param set hashes match, just load from the disk */
953
    if (crc32_value == hash_value.toUInt()) {
954 955 956 957
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());

        int count = cacheMap.count();
        int index = 0;
958
        for (const QString& name: cacheMap.keys()) {
959 960
            const ParamTypeVal& paramTypeVal = cacheMap[name];
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
961
            const int mavType = _factTypeToMavType(fact_type);
962
            _parameterUpdate(vehicleId, componentId, name, count, index++, mavType, paramTypeVal.second);
963
        }
964

965 966 967
        // 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
968
        memset(&p, 0, sizeof(p));
969 970 971 972 973 974 975
        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;
976 977 978 979 980
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
                                          _vehicle->priorityLink()->mavlinkChannel(),
                                          &msg,
                                          &p);
981
        _vehicle->sendMessageOnLinkThreadSafe(_vehicle->priorityLink(), msg);
982 983 984 985 986 987 988 989

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

990
        connect(ani, &QVariantAnimation::valueChanged, this, [this](const QVariant &value) {
991
            _setLoadProgress(value.toDouble());
992 993 994
        });

        // Hide 500ms after animation finishes
995 996
        connect(ani, &QVariantAnimation::finished, this, [this] {
            QTimer::singleShot(500, [this] {
997
                _setLoadProgress(0);
998 999 1000 1001
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
DonLakeFlyer's avatar
DonLakeFlyer committed
1002
    } else {
1003 1004 1005
        // Cache parameter version may differ from vehicle parameter version so we can't trust information loaded from cache parameter version number
        _parameterSetMajorVersion = -1;
        qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
1006 1007 1008
        if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
            _debugCacheCRC[componentId] = true;
            _debugCacheMap[componentId] = cacheMap;
1009
            for (const QString& name: cacheMap.keys()) {
1010 1011
                _debugCacheParamSeen[componentId][name] = false;
            }
1012
            qgcApp()->showAppMessage(tr("Parameter cache CRC match failed"));
1013
        }
1014
        _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_clearPX4ParameterMetaData();
Don Gagne's avatar
Don Gagne committed
1015
    }
1016 1017
}

1018
QString ParameterManager::readParametersFromStream(QTextStream& stream)
1019
{
1020 1021
    QString missingErrors;
    QString typeErrors;
dogmaphobic's avatar
dogmaphobic committed
1022

1023 1024 1025 1026 1027 1028
    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
1029 1030
                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
1031 1032
                }

1033 1034 1035 1036
                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
1037

1038
                if (!parameterExists(componentId, paramName)) {
1039
                    QString error;
1040 1041 1042
                    error += QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
                    missingErrors += error;
                    qCDebug(ParameterManagerLog) << QStringLiteral("Skipped due to missing: %1").arg(error);
1043 1044
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
1045

1046
                Fact* fact = getParameter(componentId, paramName);
1047
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
1048
                    QString error;
1049 1050 1051
                    error  = QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
                    typeErrors += error;
                    qCDebug(ParameterManagerLog) << QStringLiteral("Skipped due to type mismatch: %1").arg(error);
1052 1053
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
1054

1055
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
1056
                fact->setRawValue(valStr);
1057 1058 1059
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1060

1061 1062 1063 1064 1065 1066 1067 1068 1069 1070
    QString errors;

    if (!missingErrors.isEmpty()) {
        errors = tr("Parameters not loaded since they are not currently on the vehicle: %1\n").arg(missingErrors);
    }

    if (!typeErrors.isEmpty()) {
        errors += tr("Parameters not loaded due to type mismatch: %1").arg(typeErrors);
    }

1071
    return errors;
1072 1073
}

1074
void ParameterManager::writeParametersToStream(QTextStream& stream)
1075
{
Don Gagne's avatar
Don Gagne committed
1076
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087
    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";

1088
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
1089
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
1090

1091 1092
    for (int componentId: _mapParameterName2Variant.keys()) {
        for (const QString &paramName: _mapParameterName2Variant[componentId].keys()) {
1093
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
1094 1095 1096 1097 1098
            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";
            }
1099 1100
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1101

1102 1103 1104
    stream.flush();
}

1105
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
1106 1107
{
    switch (factType) {
1108 1109
    case FactMetaData::valueTypeUint8:
        return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
1110

1111 1112
    case FactMetaData::valueTypeInt8:
        return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
1113

1114 1115
    case FactMetaData::valueTypeUint16:
        return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
1116

1117 1118
    case FactMetaData::valueTypeInt16:
        return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
1119

1120 1121
    case FactMetaData::valueTypeUint32:
        return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
1122

1123 1124 1125 1126 1127 1128
    case FactMetaData::valueTypeUint64:
        return MAV_PARAM_TYPE_UINT64;

    case FactMetaData::valueTypeInt64:
        return MAV_PARAM_TYPE_INT64;

1129 1130
    case FactMetaData::valueTypeFloat:
        return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
1131

1132 1133 1134
    case FactMetaData::valueTypeDouble:
        return MAV_PARAM_TYPE_REAL64;

1135 1136 1137
    default:
        qWarning() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1138

1139 1140
    case FactMetaData::valueTypeInt32:
        return MAV_PARAM_TYPE_INT32;
1141 1142 1143
    }
}

1144
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
1145 1146
{
    switch (mavType) {
1147 1148
    case MAV_PARAM_TYPE_UINT8:
        return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
1149

1150 1151
    case MAV_PARAM_TYPE_INT8:
        return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
1152

1153 1154
    case MAV_PARAM_TYPE_UINT16:
        return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
1155

1156 1157
    case MAV_PARAM_TYPE_INT16:
        return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
1158

1159 1160
    case MAV_PARAM_TYPE_UINT32:
        return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
1161

1162 1163 1164 1165 1166 1167
    case MAV_PARAM_TYPE_UINT64:
        return FactMetaData::valueTypeUint64;

    case MAV_PARAM_TYPE_INT64:
        return FactMetaData::valueTypeInt64;

1168 1169
    case MAV_PARAM_TYPE_REAL32:
        return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
1170

1171 1172 1173
    case MAV_PARAM_TYPE_REAL64:
        return FactMetaData::valueTypeDouble;

1174 1175 1176
    default:
        qWarning() << "Unsupported mav param type" << mavType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1177

1178 1179
    case MAV_PARAM_TYPE_INT32:
        return FactMetaData::valueTypeInt32;
1180 1181 1182
    }
}

1183 1184 1185 1186 1187 1188
void ParameterManager::_addMetaDataToDefaultComponent(void)
{
    if (_metaDataAddedToFacts) {
        return;
    }
    _metaDataAddedToFacts = true;
1189

1190 1191 1192 1193 1194 1195 1196 1197 1198 1199
    _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_parameterMajorVersionKnown(_parameterSetMajorVersion);

    if (_mapParameterName2Variant.contains(MAV_COMP_ID_AUTOPILOT1)) {
        // Loop over all parameters in autopilot component adding meta data
        QVariantMap& factMap = _mapParameterName2Variant[MAV_COMP_ID_AUTOPILOT1];
        for (const QString& key: factMap.keys()) {
            Fact* fact = factMap[key].value<Fact*>();
            FactMetaData* factMetaData = _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->factMetaDataForName(key, fact->type());
            fact->setMetaData(factMetaData);
        }
1200 1201 1202
    }
}

1203
void ParameterManager::_checkInitialLoadComplete(void)
1204 1205 1206 1207 1208
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1209

1210
    for (int componentId: _waitingReadParamIndexMap.keys()) {
1211 1212 1213 1214 1215
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1216

1217 1218 1219 1220 1221
    if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
        // No default component params yet, not done yet
        return;
    }

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

1225 1226
    // Parameter cache crc failure debugging
    for (int componentId: _debugCacheParamSeen.keys()) {
1227
        if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
1228
            for (const QString& paramName: _debugCacheParamSeen[componentId].keys()) {
1229 1230 1231 1232 1233 1234 1235 1236
                if (!_debugCacheParamSeen[componentId][paramName]) {
                    qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
                }
            }
        }
    }
    _debugCacheCRC.clear();

1237
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Initial load complete";
1238

1239 1240 1241
    // Check for index based load failures
    QString indexList;
    bool initialLoadFailures = false;
1242 1243
    for (int componentId: _failedReadParamIndexMap.keys()) {
        for (int paramIndex: _failedReadParamIndexMap[componentId]) {
1244 1245 1246
            if (initialLoadFailures) {
                indexList += ", ";
            }
1247
            indexList += QString("%1:%2").arg(componentId).arg(paramIndex);
1248
            initialLoadFailures = true;
1249
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1250 1251
        }
    }
1252 1253

    _missingParameters = false;
1254
    if (initialLoadFailures) {
1255
        _missingParameters = true;
1256 1257
        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. "
1258
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1259
                              "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());
1260
        qCDebug(ParameterManagerLog) << errorMsg;
1261
        qgcApp()->showAppMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
1262
        if (!qgcApp()->runningUnitTests()) {
1263
            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
1264
        }
1265 1266
    }

1267
    // Signal load complete
1268
    _parametersReady = true;
1269 1270 1271
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1272
}
1273

1274
void ParameterManager::_initialRequestTimeout(void)
1275
{
1276
    if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
1277
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Retrying initial parameter request list";
1278 1279
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
1280 1281
    } else {
        if (!_vehicle->genericFirmware()) {
Don Gagne's avatar
Don Gagne committed
1282
            QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1283
                                  "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(qgcApp()->applicationName());
1284
            qCDebug(ParameterManagerLog) << errorMsg;
1285
            qgcApp()->showAppMessage(errorMsg);
1286
        }
1287
    }
1288
}
1289

1290
/// Remap a parameter from one firmware version to another
1291
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302
{
    QString mappedParamName;

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

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

1303
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315

    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
1316
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1317 1318 1319 1320 1321
        return mappedParamName;
    }

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

1322
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1323 1324 1325 1326 1327 1328 1329

    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];
1330
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1331 1332 1333 1334 1335 1336 1337
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1338 1339

/// The offline editing vehicle can have custom loaded params bolted into it.
1340
void ParameterManager::_loadOfflineEditingParams(void)
1341
{
1342 1343 1344 1345 1346 1347 1348
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1349
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363
    }

    QTextStream paramStream(&paramFile);

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

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

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

1364 1365
        int defaultComponentId = paramData.at(1).toInt();
        _vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398
        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;
        }

1399 1400 1401 1402 1403
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1404 1405
        Fact* fact = new Fact(defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact);
1406 1407
    }

1408
    _setupDefaultComponentCategoryMap();
1409 1410
    _parametersReady = true;
    _initialLoadComplete = true;
1411
    _debugCacheCRC.clear();
1412
}
1413

1414
void ParameterManager::resetAllParametersToDefaults()
1415
{
1416 1417 1418 1419 1420
    _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
1421 1422
}

1423 1424 1425 1426 1427 1428 1429 1430 1431
void ParameterManager::resetAllToVehicleConfiguration()
{
    //-- https://github.com/PX4/Firmware/pull/11760
    Fact* sysAutoConfigFact = getParameter(-1, "SYS_AUTOCONFIG");
    if(sysAutoConfigFact) {
        sysAutoConfigFact->setRawValue(2);
    }
}

1432 1433 1434 1435 1436 1437 1438 1439
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);
    }
}
1440 1441 1442

void ParameterManager::_setLoadProgress(double loadProgress)
{
1443 1444 1445 1446
    if (_loadProgress != loadProgress) {
        _loadProgress = loadProgress;
        emit loadProgressChanged(static_cast<float>(loadProgress));
    }
1447
}
Don Gagne's avatar
Don Gagne committed
1448 1449 1450 1451 1452

QList<int> ParameterManager::componentIds(void)
{
    return _paramCountMap.keys();
}
1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463

bool ParameterManager::pendingWrites(void)
{
    for (int compId: _waitingWriteParamNameMap.keys()) {
        if (_waitingWriteParamNameMap[compId].count()) {
            return true;
        }
    }

    return false;
}