ParameterManager.cc 53.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
    , _loadProgress                     (0.0)
    , _parametersReady                  (false)
    , _missingParameters                (false)
    , _initialLoadComplete              (false)
    , _waitingForDefaultComponent       (false)
    , _saveRequired                     (false)
    , _metaDataAddedToFacts             (false)
84
    , _logReplay                        (vehicle->vehicleLinkManager()->primaryLink() && vehicle->vehicleLinkManager()->primaryLink()->isLogReplay())
85 86 87 88 89 90 91
    , _prevWaitingReadParamIndexCount   (0)
    , _prevWaitingReadParamNameCount    (0)
    , _prevWaitingWriteParamNameCount   (0)
    , _initialRequestRetryCount         (0)
    , _disableAllRetries                (false)
    , _indexBatchQueueActive            (false)
    , _totalParamCount                  (0)
92
{
93 94 95 96 97 98
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

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

100
    _initialRequestTimeoutTimer.setSingleShot(true);
101
    _initialRequestTimeoutTimer.setInterval(5000);
102
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
103

104
    _waitingParamTimeoutTimer.setSingleShot(true);
105
    _waitingParamTimeoutTimer.setInterval(3000);
106
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
107

108 109
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
110 111
}

112 113 114 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
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;
    }
}

169 170

void ParameterManager::mavlinkMessageReceived(mavlink_message_t message)
171
{
172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213
    if (message.msgid == MAVLINK_MSG_ID_PARAM_VALUE) {
        mavlink_param_value_t param_value;
        mavlink_msg_param_value_decode(&message, &param_value);

        // This will null terminate the name string
        QByteArray bytes(param_value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
        QString parameterName(bytes);

        mavlink_param_union_t paramUnion;
        paramUnion.param_float  = param_value.param_value;
        paramUnion.type         = param_value.param_type;

        QVariant parameterValue;

        switch (paramUnion.type) {
        case MAV_PARAM_TYPE_REAL32:
            parameterValue = QVariant(paramUnion.param_float);
            break;
        case MAV_PARAM_TYPE_UINT8:
            parameterValue = QVariant(paramUnion.param_uint8);
            break;
        case MAV_PARAM_TYPE_INT8:
            parameterValue = QVariant(paramUnion.param_int8);
            break;
        case MAV_PARAM_TYPE_UINT16:
            parameterValue = QVariant(paramUnion.param_uint16);
            break;
        case MAV_PARAM_TYPE_INT16:
            parameterValue = QVariant(paramUnion.param_int16);
            break;
        case MAV_PARAM_TYPE_UINT32:
            parameterValue = QVariant(paramUnion.param_uint32);
            break;
        case MAV_PARAM_TYPE_INT32:
            parameterValue = QVariant(paramUnion.param_int32);
            break;
        default:
            qCritical() << "ParameterManager::_handleParamValue - unsupported MAV_PARAM_TYPE" << paramUnion.type;
            break;
        }

        _handleParamValue(message.compid, parameterName, param_value.param_count, param_value.param_index, static_cast<MAV_PARAM_TYPE>(param_value.param_type), parameterValue);
214
    }
215 216 217 218 219
}

/// Called whenever a parameter is updated or first seen.
void ParameterManager::_handleParamValue(int componentId, QString parameterName, int parameterCount, int parameterIndex, MAV_PARAM_TYPE mavParamType, QVariant parameterValue)
{
dogmaphobic's avatar
dogmaphobic committed
220

221 222 223 224
    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
                                            "_parameterUpdate" <<
                                            "name:" << parameterName <<
                                            "count:" << parameterCount <<
225 226 227
                                            "index:" << parameterIndex <<
                                            "mavType:" << mavParamType <<
                                            "value:" << parameterValue <<
228
                                            ")";
229

230 231
    // 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.
232
    if (parameterIndex == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
Patrick José Pereira's avatar
Patrick José Pereira committed
233
        qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to initial list response" << parameterName;
234 235 236
        return;
    }

237
    _initialRequestTimeoutTimer.stop();
dogmaphobic's avatar
dogmaphobic committed
238

239
#if 0
240 241 242 243 244 245 246
    if (!_initialLoadComplete && !_indexBatchQueueActive) {
        // Handy for testing retry logic
        static int counter = 0;
        if (counter++ & 0x8) {
            qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
            return;
        }
247 248
    }
#endif
249

250 251 252 253 254 255 256
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

257 258 259
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
        if (!_initialLoadComplete && !_logReplay) {
            /* we received a cache hash, potentially load from cache */
260
            _tryCacheHashLoad(_vehicle->id(), componentId, parameterValue);
261 262
        }
        return;
263
    }
264

265 266 267
    // Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog)
    if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
        if (_debugCacheMap[componentId].contains(parameterName)) {
268 269 270 271
            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         = parameterValue.constData();
272 273

            if (memcmp(cacheData, vehicleData, dataSize)) {
274
                qDebug() << "Cache/Vehicle values differ for name:cache:actual" << parameterName << parameterValue << cacheParamTypeVal.second;
275 276 277 278 279 280 281
            }
            _debugCacheParamSeen[componentId][parameterName] = true;
        } else {
            qDebug() << "Parameter missing from cache" << parameterName;
        }
    }

282
    _initialRequestTimeoutTimer.stop();
283
    _waitingParamTimeoutTimer.stop();
284

285 286 287 288 289
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
290

291
    // If we've never seen this component id before, setup the index wait lists.
292
    if (!_waitingReadParamIndexMap.contains(componentId)) {
293 294 295 296
        // 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;
297
        }
dogmaphobic's avatar
dogmaphobic committed
298

299 300 301
        // 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
302

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

306
    if (!_waitingReadParamIndexMap[componentId].contains(parameterIndex) &&
307 308
            !_waitingReadParamNameMap[componentId].contains(parameterName) &&
            !_waitingWriteParamNameMap[componentId].contains(parameterName)) {
309
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Unrequested param update" << parameterName;
310 311
    }

312
    // Remove this parameter from the waiting lists
313 314 315
    if (_waitingReadParamIndexMap[componentId].contains(parameterIndex)) {
        _waitingReadParamIndexMap[componentId].remove(parameterIndex);
        _indexBatchQueue.removeOne(parameterIndex);
316 317
        _fillIndexBatchQueue(false /* waitingParamTimeout */);
    }
318 319
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
320 321 322 323 324 325 326 327 328
    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];
    }
329 330

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

332 333 334
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
335

336
    for(int waitingComponentId: _waitingReadParamIndexMap.keys()) {
337 338 339
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
340
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
341 342
    }

343
    for(int waitingComponentId: _waitingReadParamNameMap.keys()) {
344 345 346
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
347
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
348
    }
dogmaphobic's avatar
dogmaphobic committed
349

350
    for(int waitingComponentId: _waitingWriteParamNameMap.keys()) {
351 352 353
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
354
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
355
    }
dogmaphobic's avatar
dogmaphobic committed
356

Don Gagne's avatar
Don Gagne committed
357 358 359
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
360 361
        // More params to wait for, restart timer
        _waitingParamTimeoutTimer.start();
362
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
363
    } else {
364
        if (!_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
365
            // Still waiting for parameters from default component
366
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
367 368
            _waitingParamTimeoutTimer.start();
        } else {
369
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
370
        }
371
    }
372 373
\
    _updateProgressBar();
dogmaphobic's avatar
dogmaphobic committed
374

375 376 377 378
    Fact* fact = nullptr;
    if (_mapCompId2FactMap.contains(componentId) && _mapCompId2FactMap[componentId].contains(parameterName)) {
        fact = _mapCompId2FactMap[componentId][parameterName];
    } else {
379
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Adding new fact" << parameterName;
dogmaphobic's avatar
dogmaphobic committed
380

381 382 383
        fact = new Fact(componentId, parameterName, mavTypeToFactType(mavParamType), this);
        FactMetaData* factMetaData = _vehicle->compInfoManager()->compInfoParam(componentId)->factMetaDataForName(parameterName, fact->type());
        fact->setMetaData(factMetaData);
dogmaphobic's avatar
dogmaphobic committed
384

385
        _mapCompId2FactMap[componentId][parameterName] = fact;
dogmaphobic's avatar
dogmaphobic committed
386

387 388
        // We need to know when the fact value changes so we can update the vehicle
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterManager::_factRawValueUpdated);
dogmaphobic's avatar
dogmaphobic committed
389

390
        emit factAdded(componentId, fact);
391
    }
dogmaphobic's avatar
dogmaphobic committed
392

Don Gagne's avatar
Don Gagne committed
393 394
    _dataMutex.unlock();

395
    fact->_containerSetRawValue(parameterValue);
396

Don Gagne's avatar
Don Gagne committed
397 398 399
    // 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.
400
    if (!_logReplay && _vehicle->px4Firmware()) {
Don Gagne's avatar
Don Gagne committed
401 402
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
            // All reads just finished, update the cache
403
            _writeLocalParamCache(_vehicle->id(), componentId);
Don Gagne's avatar
Don Gagne committed
404 405 406 407 408 409 410
        }
    }

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

411
    _checkInitialLoadComplete();
412 413

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
414 415
}

416 417
/// Writes the parameter update to mavlink, sets up for write wait
void ParameterManager::_factRawValueUpdateWorker(int componentId, const QString& name, FactMetaData::ValueType_t valueType, const QVariant& rawValue)
418
{
419
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
420

DonLakeFlyer's avatar
DonLakeFlyer committed
421
    if (_waitingWriteParamNameMap.contains(componentId)) {
422 423 424 425 426 427 428
        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
429 430 431
        _waitingParamTimeoutTimer.start();
        _saveRequired = true;
    } else {
432
        qWarning() << "Internal error ParameterManager::_factValueUpdateWorker: component id not found" << componentId;
DonLakeFlyer's avatar
DonLakeFlyer committed
433
    }
dogmaphobic's avatar
dogmaphobic committed
434

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

437 438 439 440 441 442 443 444 445 446 447 448 449
    _sendParamSetToVehicle(componentId, name, valueType, rawValue);
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Update parameter (_waitingParamTimeoutTimer started) - compId:name:rawValue" << componentId << name << rawValue;
}

void ParameterManager::_factRawValueUpdated(const QVariant& rawValue)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    if (!fact) {
        qWarning() << "Internal error";
        return;
    }

    _factRawValueUpdateWorker(fact->componentId(), fact->name(), fact->type(), rawValue);
450 451
}

452
void ParameterManager::refreshAllParameters(uint8_t componentId)
453
{
454 455 456 457 458
    if (!_vehicle->vehicleLinkManager()->primaryLink()) {
        return;
    }

    if (_vehicle->vehicleLinkManager()->primaryLink()->linkConfiguration()->isHighLatency() || _logReplay) {
459 460 461 462 463 464 465
        // 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
466 467
    }

468
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
469

470 471 472 473
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

474
    // Reset index wait lists
475
    for (int cid: _paramCountMap.keys()) {
476
        // Add/Update all indices to the wait list, parameter index is 0-based
477
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
478 479
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
480
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
481
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
482 483
        }
    }
dogmaphobic's avatar
dogmaphobic committed
484

485
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
486

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

489
    mavlink_message_t msg;
490 491
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
492
                                             _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
493 494
                                             &msg,
                                             _vehicle->id(),
495
                                             componentId);
496
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
497

498
    QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
499
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
500 501 502
}

/// Translates FactSystem::defaultComponentId to real component id if needed
503
int ParameterManager::_actualComponentId(int componentId)
504 505
{
    if (componentId == FactSystem::defaultComponentId) {
506
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
507
        if (componentId == FactSystem::defaultComponentId) {
508
            qWarning() << _logVehiclePrefix(-1) << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
509
        }
510
    }
dogmaphobic's avatar
dogmaphobic committed
511

512 513 514
    return componentId;
}

515
void ParameterManager::refreshParameter(int componentId, const QString& paramName)
516
{
517
    componentId = _actualComponentId(componentId);
518
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
dogmaphobic's avatar
dogmaphobic committed
519

520 521 522
    _dataMutex.lock();

    if (_waitingReadParamNameMap.contains(componentId)) {
523
        QString mappedParamName = _remapParamNameToVersion(paramName);
524

525 526 527 528 529
        if (_waitingReadParamNameMap[componentId].contains(mappedParamName)) {
            _waitingReadParamNameMap[componentId].remove(mappedParamName);
        } else {
            _waitingReadParamNameBatchCount++;
        }
530
        _waitingReadParamNameMap[componentId][mappedParamName] = 0;     // Add new wait entry and update retry count
531
        _updateProgressBar();
532 533
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
534 535
    } else {
        qWarning() << "Internal error";
536
    }
dogmaphobic's avatar
dogmaphobic committed
537

538 539
    _dataMutex.unlock();

540
    _readParameterRaw(componentId, paramName, -1);
541 542
}

543
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
544 545
{
    componentId = _actualComponentId(componentId);
546
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
547

548
    for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
549 550
        if (paramName.startsWith(namePrefix)) {
            refreshParameter(componentId, paramName);
551 552 553 554
        }
    }
}

555
bool ParameterManager::parameterExists(int componentId, const QString& paramName)
556
{
557
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
558

559
    componentId = _actualComponentId(componentId);
560 561
    if (_mapCompId2FactMap.contains(componentId)) {
        ret = _mapCompId2FactMap[componentId].contains(_remapParamNameToVersion(paramName));
562
    }
563 564

    return ret;
565 566
}

567
Fact* ParameterManager::getParameter(int componentId, const QString& paramName)
568 569
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
570

571
    QString mappedParamName = _remapParamNameToVersion(paramName);
572
    if (!_mapCompId2FactMap.contains(componentId) || !_mapCompId2FactMap[componentId].contains(mappedParamName)) {
573
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
574
        return &_defaultFact;
575
    }
dogmaphobic's avatar
dogmaphobic committed
576

577
    return _mapCompId2FactMap[componentId][mappedParamName];
578
}
579

580
QStringList ParameterManager::parameterNames(int componentId)
581
{
dogmaphobic's avatar
dogmaphobic committed
582 583
    QStringList names;

584
    for(const QString &paramName: _mapCompId2FactMap[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
585 586 587 588
        names << paramName;
    }

    return names;
589 590
}

591 592 593 594
/// 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)
595
{
596 597 598
    if (!_indexBatchQueueActive) {
        return false;
    }
dogmaphobic's avatar
dogmaphobic committed
599

600
    const int maxBatchSize = 10;
601

602 603 604 605 606 607 608
    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";
    }
609

610
    for(int componentId: _waitingReadParamIndexMap.keys()) {
611
        if (_waitingReadParamIndexMap[componentId].count()) {
612 613
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
614 615
        }

616
        for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
617 618 619 620 621 622 623
            if (_indexBatchQueue.contains(paramIndex)) {
                // Don't add more than once
                continue;
            }

            if (_indexBatchQueue.count() > maxBatchSize) {
                break;
624 625
            }

626
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
627
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
628 629
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
630
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
631 632 633
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
634
                _indexBatchQueue.append(paramIndex);
635
                _readParameterRaw(componentId, "", paramIndex);
636
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
637 638 639
            }
        }
    }
640

641 642 643 644 645
    return _indexBatchQueue.count() != 0;
}

void ParameterManager::_waitingParamTimeout(void)
{
646 647 648 649
    if (_logReplay) {
        return;
    }

650 651 652 653
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;

654
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
655 656 657 658 659 660 661

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

662
    if (!paramsRequested && !_waitingForDefaultComponent && !_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
663 664
        // 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.
665
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId();
666 667 668 669 670 671
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

672
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
673

674
    if (!paramsRequested) {
675 676
        for(int componentId: _waitingWriteParamNameMap.keys()) {
            for(const QString &paramName: _waitingWriteParamNameMap[componentId].keys()) {
677
                paramsRequested = true;
678
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
679
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
680 681
                    Fact* fact = getParameter(componentId, paramName);
                    _sendParamSetToVehicle(componentId, paramName, fact->type(), fact->rawValue());
682
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
683
                    if (++batchCount > maxBatchSize) {
684 685 686 687 688
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
689 690
                    QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
691
                    qgcApp()->showAppMessage(errorMsg);
692 693 694 695
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
696

697
    if (!paramsRequested) {
698 699
        for(int componentId: _waitingReadParamNameMap.keys()) {
            for(const QString &paramName: _waitingReadParamNameMap[componentId].keys()) {
700
                paramsRequested = true;
701
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
702 703
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
704
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
705
                    if (++batchCount > maxBatchSize) {
706 707 708 709 710
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
711 712
                    QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
713
                    qgcApp()->showAppMessage(errorMsg);
714 715 716 717
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
718

719 720
Out:
    if (paramsRequested) {
721
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
722 723 724 725
        _waitingParamTimeoutTimer.start();
    }
}

726
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
727 728 729 730 731
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
732 733
    mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(),   // QGC system id
                                             _mavlink->getComponentId(),     // QGC component id
734
                                             _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
735 736 737 738 739
                                             &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
740
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
741 742
}

743
void ParameterManager::_sendParamSetToVehicle(int componentId, const QString& paramName, FactMetaData::ValueType_t valueType, const QVariant& value)
744 745 746
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
747

Don Gagne's avatar
Don Gagne committed
748 749
    memset(&p, 0, sizeof(p));

750
    p.param_type = factTypeToMavType(valueType);
dogmaphobic's avatar
dogmaphobic committed
751

752
    switch (valueType) {
753 754 755
    case FactMetaData::valueTypeUint8:
        union_value.param_uint8 = (uint8_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
756

757 758 759
    case FactMetaData::valueTypeInt8:
        union_value.param_int8 = (int8_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
760

761 762 763
    case FactMetaData::valueTypeUint16:
        union_value.param_uint16 = (uint16_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
764

765 766 767
    case FactMetaData::valueTypeInt16:
        union_value.param_int16 = (int16_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
768

769 770 771
    case FactMetaData::valueTypeUint32:
        union_value.param_uint32 = (uint32_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
772

773 774 775
    case FactMetaData::valueTypeFloat:
        union_value.param_float = value.toFloat();
        break;
dogmaphobic's avatar
dogmaphobic committed
776

777
    default:
778
        qCritical() << "Unsupported fact falue type" << valueType;
779
        // fall through
dogmaphobic's avatar
dogmaphobic committed
780

781 782 783
    case FactMetaData::valueTypeInt32:
        union_value.param_int32 = (int32_t)value.toInt();
        break;
784
    }
dogmaphobic's avatar
dogmaphobic committed
785

786
    p.param_value = union_value.param_float;
787
    p.target_system = (uint8_t)_vehicle->id();
788
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
789

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

792
    mavlink_message_t msg;
793 794
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
795
                                      _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
796 797
                                      &msg,
                                      &p);
798
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
799 800
}

801
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
802
{
803
    CacheMapName2ParamTypeVal cacheMap;
804

805 806
    for (const QString& paramName: _mapCompId2FactMap[componentId].keys()) {
        const Fact *fact = _mapCompId2FactMap[componentId][paramName];
807
        cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
808 809
    }

810 811
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
812

813 814
    QDataStream ds(&cacheFile);
    ds << cacheMap;
815 816
}

817
QDir ParameterManager::parameterCacheDir()
818 819 820 821 822
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

823
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
824
{
825
    return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
826 827
}

828
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
829
{
830 831
    qCInfo(ParameterManagerLog) << "Attemping load from cache";

832 833
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
834 835 836
    CacheMapName2ParamTypeVal cacheMap;
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    if (!cacheFile.exists()) {
837
        /* no local cache, just wait for them to come in*/
838 839
        return;
    }
840
    cacheFile.open(QIODevice::ReadOnly);
841 842

    /* Deserialize the parameter cache table */
843 844 845
    QDataStream ds(&cacheFile);
    ds >> cacheMap;

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

848
    for (const QString& name: cacheMap.keys()) {
849
        if (_vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_isParameterVolatile(name)) {
850 851 852 853 854 855 856 857 858
            // 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);
        }
859 860
    }

861
    /* if the two param set hashes match, just load from the disk */
862
    if (crc32_value == hash_value.toUInt()) {
863 864 865 866
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());

        int count = cacheMap.count();
        int index = 0;
867
        for (const QString& name: cacheMap.keys()) {
868 869
            const ParamTypeVal& paramTypeVal = cacheMap[name];
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
870 871
            const MAV_PARAM_TYPE mavParamType = factTypeToMavType(fact_type);
            _handleParamValue(componentId, name, count, index++, mavParamType, paramTypeVal.second);
872
        }
873

874 875 876
        // 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
877
        memset(&p, 0, sizeof(p));
878 879 880 881 882 883 884
        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;
885 886
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
887
                                          _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
888 889
                                          &msg,
                                          &p);
890
        _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
891 892 893 894 895 896 897 898

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

899
        connect(ani, &QVariantAnimation::valueChanged, this, [this](const QVariant &value) {
900
            _setLoadProgress(value.toDouble());
901 902 903
        });

        // Hide 500ms after animation finishes
904 905
        connect(ani, &QVariantAnimation::finished, this, [this] {
            QTimer::singleShot(500, [this] {
906
                _setLoadProgress(0);
907 908 909 910
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
DonLakeFlyer's avatar
DonLakeFlyer committed
911
    } else {
912
        qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
913 914 915
        if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
            _debugCacheCRC[componentId] = true;
            _debugCacheMap[componentId] = cacheMap;
916
            for (const QString& name: cacheMap.keys()) {
917 918
                _debugCacheParamSeen[componentId][name] = false;
            }
919
            qgcApp()->showAppMessage(tr("Parameter cache CRC match failed"));
920
        }
Don Gagne's avatar
Don Gagne committed
921
    }
922 923
}

924
QString ParameterManager::readParametersFromStream(QTextStream& stream)
925
{
926 927
    QString missingErrors;
    QString typeErrors;
dogmaphobic's avatar
dogmaphobic committed
928

929 930 931 932 933 934
    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
935 936
                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
937 938
                }

939 940 941 942
                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
943

944
                if (!parameterExists(componentId, paramName)) {
945
                    QString error;
946 947 948
                    error += QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
                    missingErrors += error;
                    qCDebug(ParameterManagerLog) << QStringLiteral("Skipped due to missing: %1").arg(error);
949 950
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
951

952
                Fact* fact = getParameter(componentId, paramName);
953
                if (fact->type() != mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
954
                    QString error;
955 956 957
                    error  = QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
                    typeErrors += error;
                    qCDebug(ParameterManagerLog) << QStringLiteral("Skipped due to type mismatch: %1").arg(error);
958 959
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
960

961
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
962
                fact->setRawValue(valStr);
963 964 965
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
966

967 968 969 970 971 972 973 974 975 976
    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);
    }

977
    return errors;
978 979
}

980
void ParameterManager::writeParametersToStream(QTextStream& stream)
981
{
Don Gagne's avatar
Don Gagne committed
982
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
983 984 985 986 987 988 989 990 991 992 993
    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";

994
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
995
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
996

997 998 999
    for (int componentId: _mapCompId2FactMap.keys()) {
        for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
            Fact* fact = _mapCompId2FactMap[componentId][paramName];
1000
            if (fact) {
1001
                stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QString("%1").arg(factTypeToMavType(fact->type())) << "\n";
1002 1003 1004
            } else {
                qWarning() << "Internal error: missing fact";
            }
1005 1006
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1007

1008 1009 1010
    stream.flush();
}

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

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

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

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

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

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

    case FactMetaData::valueTypeInt64:
        return MAV_PARAM_TYPE_INT64;

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

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

1041 1042 1043
    default:
        qWarning() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1044

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

1050
FactMetaData::ValueType_t ParameterManager::mavTypeToFactType(MAV_PARAM_TYPE mavType)
1051 1052
{
    switch (mavType) {
1053 1054
    case MAV_PARAM_TYPE_UINT8:
        return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
1055

1056 1057
    case MAV_PARAM_TYPE_INT8:
        return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
1058

1059 1060
    case MAV_PARAM_TYPE_UINT16:
        return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
1061

1062 1063
    case MAV_PARAM_TYPE_INT16:
        return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
1064

1065 1066
    case MAV_PARAM_TYPE_UINT32:
        return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
1067

1068 1069 1070 1071 1072 1073
    case MAV_PARAM_TYPE_UINT64:
        return FactMetaData::valueTypeUint64;

    case MAV_PARAM_TYPE_INT64:
        return FactMetaData::valueTypeInt64;

1074 1075
    case MAV_PARAM_TYPE_REAL32:
        return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
1076

1077 1078 1079
    case MAV_PARAM_TYPE_REAL64:
        return FactMetaData::valueTypeDouble;

1080 1081 1082
    default:
        qWarning() << "Unsupported mav param type" << mavType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1083

1084 1085
    case MAV_PARAM_TYPE_INT32:
        return FactMetaData::valueTypeInt32;
1086 1087 1088
    }
}

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

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

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

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

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

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

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

    _missingParameters = false;
1140
    if (initialLoadFailures) {
1141
        _missingParameters = true;
1142 1143
        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. "
1144
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1145
                              "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());
1146
        qCDebug(ParameterManagerLog) << errorMsg;
1147
        qgcApp()->showAppMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
1148
        if (!qgcApp()->runningUnitTests()) {
1149
            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
1150
        }
1151 1152
    }

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

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

1176
/// Remap a parameter from one firmware version to another
1177
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188
{
    QString mappedParamName;

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

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

1189
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201

    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
1202
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1203 1204 1205 1206 1207
        return mappedParamName;
    }

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

1208
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1209 1210 1211 1212 1213 1214 1215

    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];
1216
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1217 1218 1219 1220 1221 1222 1223
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1224 1225

/// The offline editing vehicle can have custom loaded params bolted into it.
1226
void ParameterManager::_loadOfflineEditingParams(void)
1227
{
1228 1229 1230 1231 1232 1233 1234
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1235
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249
    }

    QTextStream paramStream(&paramFile);

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

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

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

1250 1251
        int defaultComponentId = paramData.at(1).toInt();
        _vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284
        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;
        }

1285 1286 1287 1288
        Fact* fact = new Fact(defaultComponentId, paramName, mavTypeToFactType(paramType), this);

        FactMetaData* factMetaData = _vehicle->compInfoManager()->compInfoParam(defaultComponentId)->factMetaDataForName(paramName, fact->type());
        fact->setMetaData(factMetaData);
1289

1290
        _mapCompId2FactMap[defaultComponentId][paramName] = fact;
1291 1292 1293 1294
    }

    _parametersReady = true;
    _initialLoadComplete = true;
1295
    _debugCacheCRC.clear();
1296
}
1297

1298
void ParameterManager::resetAllParametersToDefaults()
1299
{
1300
    _vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1,
1301 1302 1303 1304
                             MAV_CMD_PREFLIGHT_STORAGE,
                             true,  // showError
                             2,     // Reset params to default
                             -1);   // Don't do anything with mission storage
1305 1306
}

1307 1308 1309 1310 1311 1312 1313 1314 1315
void ParameterManager::resetAllToVehicleConfiguration()
{
    //-- https://github.com/PX4/Firmware/pull/11760
    Fact* sysAutoConfigFact = getParameter(-1, "SYS_AUTOCONFIG");
    if(sysAutoConfigFact) {
        sysAutoConfigFact->setRawValue(2);
    }
}

1316 1317 1318 1319 1320 1321 1322 1323
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);
    }
}
1324 1325 1326

void ParameterManager::_setLoadProgress(double loadProgress)
{
1327 1328 1329 1330
    if (_loadProgress != loadProgress) {
        _loadProgress = loadProgress;
        emit loadProgressChanged(static_cast<float>(loadProgress));
    }
1331
}
Don Gagne's avatar
Don Gagne committed
1332 1333 1334 1335 1336

QList<int> ParameterManager::componentIds(void)
{
    return _paramCountMap.keys();
}
1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347

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

    return false;
}