ParameterManager.cc 53.7 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

393
    fact->_containerSetRawValue(parameterValue);
394

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

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

409
    _checkInitialLoadComplete();
410 411

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
412 413
}

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

431 432 433 434 435 436 437 438 439 440 441 442 443
    _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);
444 445
}

446
void ParameterManager::refreshAllParameters(uint8_t componentId)
447
{
448 449 450 451 452
    if (!_vehicle->vehicleLinkManager()->primaryLink()) {
        return;
    }

    if (_vehicle->vehicleLinkManager()->primaryLink()->linkConfiguration()->isHighLatency() || _logReplay) {
453 454 455 456 457 458 459
        // 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
460 461
    }

462 463 464 465
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

466
    // Reset index wait lists
467
    for (int cid: _paramCountMap.keys()) {
468
        // Add/Update all indices to the wait list, parameter index is 0-based
469
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
470 471
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
472
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
473
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
474 475
        }
    }
dogmaphobic's avatar
dogmaphobic committed
476

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

479
    mavlink_message_t msg;
480 481
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
482
                                             _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
483 484
                                             &msg,
                                             _vehicle->id(),
485
                                             componentId);
486
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
487

488
    QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
489
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
490 491 492
}

/// Translates FactSystem::defaultComponentId to real component id if needed
493
int ParameterManager::_actualComponentId(int componentId)
494 495
{
    if (componentId == FactSystem::defaultComponentId) {
496
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
497
        if (componentId == FactSystem::defaultComponentId) {
498
            qWarning() << _logVehiclePrefix(-1) << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
499
        }
500
    }
dogmaphobic's avatar
dogmaphobic committed
501

502 503 504
    return componentId;
}

505
void ParameterManager::refreshParameter(int componentId, const QString& paramName)
506
{
507
    componentId = _actualComponentId(componentId);
508
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
dogmaphobic's avatar
dogmaphobic committed
509

510
    if (_waitingReadParamNameMap.contains(componentId)) {
511
        QString mappedParamName = _remapParamNameToVersion(paramName);
512

513 514 515 516 517
        if (_waitingReadParamNameMap[componentId].contains(mappedParamName)) {
            _waitingReadParamNameMap[componentId].remove(mappedParamName);
        } else {
            _waitingReadParamNameBatchCount++;
        }
518
        _waitingReadParamNameMap[componentId][mappedParamName] = 0;     // Add new wait entry and update retry count
519
        _updateProgressBar();
520 521
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
522 523
    } else {
        qWarning() << "Internal error";
524
    }
dogmaphobic's avatar
dogmaphobic committed
525

526
    _readParameterRaw(componentId, paramName, -1);
527 528
}

529
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
530 531
{
    componentId = _actualComponentId(componentId);
532
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
533

534
    for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
535 536
        if (paramName.startsWith(namePrefix)) {
            refreshParameter(componentId, paramName);
537 538 539 540
        }
    }
}

541
bool ParameterManager::parameterExists(int componentId, const QString& paramName)
542
{
543
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
544

545
    componentId = _actualComponentId(componentId);
546 547
    if (_mapCompId2FactMap.contains(componentId)) {
        ret = _mapCompId2FactMap[componentId].contains(_remapParamNameToVersion(paramName));
548
    }
549 550

    return ret;
551 552
}

553
Fact* ParameterManager::getParameter(int componentId, const QString& paramName)
554 555
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
556

557
    QString mappedParamName = _remapParamNameToVersion(paramName);
558
    if (!_mapCompId2FactMap.contains(componentId) || !_mapCompId2FactMap[componentId].contains(mappedParamName)) {
559
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
560
        return &_defaultFact;
561
    }
dogmaphobic's avatar
dogmaphobic committed
562

563
    return _mapCompId2FactMap[componentId][mappedParamName];
564
}
565

566
QStringList ParameterManager::parameterNames(int componentId)
567
{
dogmaphobic's avatar
dogmaphobic committed
568 569
    QStringList names;

570
    for(const QString &paramName: _mapCompId2FactMap[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
571 572 573 574
        names << paramName;
    }

    return names;
575 576
}

577 578 579 580
/// 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)
581
{
582 583 584
    if (!_indexBatchQueueActive) {
        return false;
    }
dogmaphobic's avatar
dogmaphobic committed
585

586
    const int maxBatchSize = 10;
587

588 589 590 591 592 593 594
    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";
    }
595

596
    for(int componentId: _waitingReadParamIndexMap.keys()) {
597
        if (_waitingReadParamIndexMap[componentId].count()) {
598 599
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
600 601
        }

602
        for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
603 604 605 606 607 608 609
            if (_indexBatchQueue.contains(paramIndex)) {
                // Don't add more than once
                continue;
            }

            if (_indexBatchQueue.count() > maxBatchSize) {
                break;
610 611
            }

612
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
613
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
614 615
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
616
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
617 618 619
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
620
                _indexBatchQueue.append(paramIndex);
621
                _readParameterRaw(componentId, "", paramIndex);
622
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
623 624 625
            }
        }
    }
626

627 628 629 630 631
    return _indexBatchQueue.count() != 0;
}

void ParameterManager::_waitingParamTimeout(void)
{
632 633 634 635
    if (_logReplay) {
        return;
    }

636 637 638 639
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;

640
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
641 642 643 644 645 646 647

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

648
    if (!paramsRequested && !_waitingForDefaultComponent && !_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
649 650
        // 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.
651
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId();
652 653 654 655 656 657
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

658
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
659

660
    if (!paramsRequested) {
661 662
        for(int componentId: _waitingWriteParamNameMap.keys()) {
            for(const QString &paramName: _waitingWriteParamNameMap[componentId].keys()) {
663
                paramsRequested = true;
664
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
665
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
666 667
                    Fact* fact = getParameter(componentId, paramName);
                    _sendParamSetToVehicle(componentId, paramName, fact->type(), fact->rawValue());
668
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
669
                    if (++batchCount > maxBatchSize) {
670 671 672 673 674
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
675 676
                    QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
677
                    qgcApp()->showAppMessage(errorMsg);
678 679 680 681
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
682

683
    if (!paramsRequested) {
684 685
        for(int componentId: _waitingReadParamNameMap.keys()) {
            for(const QString &paramName: _waitingReadParamNameMap[componentId].keys()) {
686
                paramsRequested = true;
687
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
688 689
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
690
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
691
                    if (++batchCount > maxBatchSize) {
692 693 694 695 696
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
697 698
                    QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
699
                    qgcApp()->showAppMessage(errorMsg);
700 701 702 703
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
704

705 706
Out:
    if (paramsRequested) {
707
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
708 709 710 711
        _waitingParamTimeoutTimer.start();
    }
}

712
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
713 714 715 716 717
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
718 719
    mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(),   // QGC system id
                                             _mavlink->getComponentId(),     // QGC component id
720
                                             _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
721 722 723 724 725
                                             &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
726
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
727 728
}

729
void ParameterManager::_sendParamSetToVehicle(int componentId, const QString& paramName, FactMetaData::ValueType_t valueType, const QVariant& value)
730 731 732
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
733

Don Gagne's avatar
Don Gagne committed
734 735
    memset(&p, 0, sizeof(p));

736
    p.param_type = factTypeToMavType(valueType);
dogmaphobic's avatar
dogmaphobic committed
737

738
    switch (valueType) {
739 740 741
    case FactMetaData::valueTypeUint8:
        union_value.param_uint8 = (uint8_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
742

743 744 745
    case FactMetaData::valueTypeInt8:
        union_value.param_int8 = (int8_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
746

747 748 749
    case FactMetaData::valueTypeUint16:
        union_value.param_uint16 = (uint16_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
750

751 752 753
    case FactMetaData::valueTypeInt16:
        union_value.param_int16 = (int16_t)value.toInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
754

755 756 757
    case FactMetaData::valueTypeUint32:
        union_value.param_uint32 = (uint32_t)value.toUInt();
        break;
dogmaphobic's avatar
dogmaphobic committed
758

759 760 761
    case FactMetaData::valueTypeFloat:
        union_value.param_float = value.toFloat();
        break;
dogmaphobic's avatar
dogmaphobic committed
762

763
    default:
764
        qCritical() << "Unsupported fact falue type" << valueType;
765
        // fall through
dogmaphobic's avatar
dogmaphobic committed
766

767 768 769
    case FactMetaData::valueTypeInt32:
        union_value.param_int32 = (int32_t)value.toInt();
        break;
770
    }
dogmaphobic's avatar
dogmaphobic committed
771

772
    p.param_value = union_value.param_float;
773
    p.target_system = (uint8_t)_vehicle->id();
774
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
775

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

778
    mavlink_message_t msg;
779 780
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
781
                                      _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
782 783
                                      &msg,
                                      &p);
784
    _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
785 786
}

787
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
788
{
789
    CacheMapName2ParamTypeVal cacheMap;
790

791 792
    for (const QString& paramName: _mapCompId2FactMap[componentId].keys()) {
        const Fact *fact = _mapCompId2FactMap[componentId][paramName];
793
        cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
794 795
    }

796 797
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
798

799 800
    QDataStream ds(&cacheFile);
    ds << cacheMap;
801 802
}

803
QDir ParameterManager::parameterCacheDir()
804 805 806 807 808
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

809
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
810
{
811
    return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
812 813
}

814
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
815
{
816 817
    qCInfo(ParameterManagerLog) << "Attemping load from cache";

818 819
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
820 821 822
    CacheMapName2ParamTypeVal cacheMap;
    QFile cacheFile(parameterCacheFile(vehicleId, componentId));
    if (!cacheFile.exists()) {
823
        /* no local cache, just wait for them to come in*/
824 825
        return;
    }
826
    cacheFile.open(QIODevice::ReadOnly);
827 828

    /* Deserialize the parameter cache table */
829 830 831
    QDataStream ds(&cacheFile);
    ds >> cacheMap;

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

834
    for (const QString& name: cacheMap.keys()) {
835
        if (_vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_isParameterVolatile(name)) {
836 837 838 839 840 841 842 843 844
            // 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);
        }
845 846
    }

847
    /* if the two param set hashes match, just load from the disk */
848
    if (crc32_value == hash_value.toUInt()) {
849 850 851 852
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());

        int count = cacheMap.count();
        int index = 0;
853
        for (const QString& name: cacheMap.keys()) {
854 855
            const ParamTypeVal& paramTypeVal = cacheMap[name];
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
856 857
            const MAV_PARAM_TYPE mavParamType = factTypeToMavType(fact_type);
            _handleParamValue(componentId, name, count, index++, mavParamType, paramTypeVal.second);
858
        }
859

860 861 862
        // 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
863
        memset(&p, 0, sizeof(p));
864 865 866 867 868 869 870
        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;
871 872
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
873
                                          _vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
874 875
                                          &msg,
                                          &p);
876
        _vehicle->sendMessageOnLinkThreadSafe(_vehicle->vehicleLinkManager()->primaryLink(), msg);
877 878 879 880 881 882 883 884

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

885
        connect(ani, &QVariantAnimation::valueChanged, this, [this](const QVariant &value) {
886
            _setLoadProgress(value.toDouble());
887 888 889
        });

        // Hide 500ms after animation finishes
890 891
        connect(ani, &QVariantAnimation::finished, this, [this] {
            QTimer::singleShot(500, [this] {
892
                _setLoadProgress(0);
893 894 895 896
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
DonLakeFlyer's avatar
DonLakeFlyer committed
897
    } else {
898
        qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
899 900 901
        if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
            _debugCacheCRC[componentId] = true;
            _debugCacheMap[componentId] = cacheMap;
902
            for (const QString& name: cacheMap.keys()) {
903 904
                _debugCacheParamSeen[componentId][name] = false;
            }
905
            qgcApp()->showAppMessage(tr("Parameter cache CRC match failed"));
906
        }
Don Gagne's avatar
Don Gagne committed
907
    }
908 909
}

910
QString ParameterManager::readParametersFromStream(QTextStream& stream)
911
{
912 913
    QString missingErrors;
    QString typeErrors;
dogmaphobic's avatar
dogmaphobic committed
914

915 916 917 918 919 920
    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
921 922
                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
923 924
                }

925 926 927 928
                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
929

930
                if (!parameterExists(componentId, paramName)) {
931
                    QString error;
932 933 934
                    error += QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
                    missingErrors += error;
                    qCDebug(ParameterManagerLog) << QStringLiteral("Skipped due to missing: %1").arg(error);
935 936
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
937

938
                Fact* fact = getParameter(componentId, paramName);
939
                if (fact->type() != mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
940
                    QString error;
941 942 943
                    error  = QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
                    typeErrors += error;
                    qCDebug(ParameterManagerLog) << QStringLiteral("Skipped due to type mismatch: %1").arg(error);
944 945
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
946

947
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
948
                fact->setRawValue(valStr);
949 950 951
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
952

953 954 955 956 957 958 959 960 961 962
    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);
    }

963
    return errors;
964 965
}

966
void ParameterManager::writeParametersToStream(QTextStream& stream)
967
{
Don Gagne's avatar
Don Gagne committed
968
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
969 970 971 972 973 974 975 976 977 978 979
    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";

980
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
981
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
982

983 984 985
    for (int componentId: _mapCompId2FactMap.keys()) {
        for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
            Fact* fact = _mapCompId2FactMap[componentId][paramName];
986
            if (fact) {
987
                stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QString("%1").arg(factTypeToMavType(fact->type())) << "\n";
988 989 990
            } else {
                qWarning() << "Internal error: missing fact";
            }
991 992
        }
    }
dogmaphobic's avatar
dogmaphobic committed
993

994 995 996
    stream.flush();
}

997
MAV_PARAM_TYPE ParameterManager::factTypeToMavType(FactMetaData::ValueType_t factType)
998 999
{
    switch (factType) {
1000 1001
    case FactMetaData::valueTypeUint8:
        return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
1002

1003 1004
    case FactMetaData::valueTypeInt8:
        return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
1005

1006 1007
    case FactMetaData::valueTypeUint16:
        return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
1008

1009 1010
    case FactMetaData::valueTypeInt16:
        return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
1011

1012 1013
    case FactMetaData::valueTypeUint32:
        return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
1014

1015 1016 1017 1018 1019 1020
    case FactMetaData::valueTypeUint64:
        return MAV_PARAM_TYPE_UINT64;

    case FactMetaData::valueTypeInt64:
        return MAV_PARAM_TYPE_INT64;

1021 1022
    case FactMetaData::valueTypeFloat:
        return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
1023

1024 1025 1026
    case FactMetaData::valueTypeDouble:
        return MAV_PARAM_TYPE_REAL64;

1027 1028 1029
    default:
        qWarning() << "Unsupported fact type" << factType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1030

1031 1032
    case FactMetaData::valueTypeInt32:
        return MAV_PARAM_TYPE_INT32;
1033 1034 1035
    }
}

1036
FactMetaData::ValueType_t ParameterManager::mavTypeToFactType(MAV_PARAM_TYPE mavType)
1037 1038
{
    switch (mavType) {
1039 1040
    case MAV_PARAM_TYPE_UINT8:
        return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
1041

1042 1043
    case MAV_PARAM_TYPE_INT8:
        return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
1044

1045 1046
    case MAV_PARAM_TYPE_UINT16:
        return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
1047

1048 1049
    case MAV_PARAM_TYPE_INT16:
        return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
1050

1051 1052
    case MAV_PARAM_TYPE_UINT32:
        return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
1053

1054 1055 1056 1057 1058 1059
    case MAV_PARAM_TYPE_UINT64:
        return FactMetaData::valueTypeUint64;

    case MAV_PARAM_TYPE_INT64:
        return FactMetaData::valueTypeInt64;

1060 1061
    case MAV_PARAM_TYPE_REAL32:
        return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
1062

1063 1064 1065
    case MAV_PARAM_TYPE_REAL64:
        return FactMetaData::valueTypeDouble;

1066 1067 1068
    default:
        qWarning() << "Unsupported mav param type" << mavType;
        // fall through
dogmaphobic's avatar
dogmaphobic committed
1069

1070 1071
    case MAV_PARAM_TYPE_INT32:
        return FactMetaData::valueTypeInt32;
1072 1073 1074
    }
}

1075
void ParameterManager::_checkInitialLoadComplete(void)
1076 1077 1078 1079 1080
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1081

1082
    for (int componentId: _waitingReadParamIndexMap.keys()) {
1083 1084 1085 1086 1087
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1088

1089
    if (!_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
1090 1091 1092 1093
        // No default component params yet, not done yet
        return;
    }

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

1097 1098
    // Parameter cache crc failure debugging
    for (int componentId: _debugCacheParamSeen.keys()) {
1099
        if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
1100
            for (const QString& paramName: _debugCacheParamSeen[componentId].keys()) {
1101 1102 1103 1104 1105 1106 1107 1108
                if (!_debugCacheParamSeen[componentId][paramName]) {
                    qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
                }
            }
        }
    }
    _debugCacheCRC.clear();

1109
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Initial load complete";
1110

1111 1112 1113
    // Check for index based load failures
    QString indexList;
    bool initialLoadFailures = false;
1114 1115
    for (int componentId: _failedReadParamIndexMap.keys()) {
        for (int paramIndex: _failedReadParamIndexMap[componentId]) {
1116 1117 1118
            if (initialLoadFailures) {
                indexList += ", ";
            }
1119
            indexList += QString("%1:%2").arg(componentId).arg(paramIndex);
1120
            initialLoadFailures = true;
1121
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1122 1123
        }
    }
1124 1125

    _missingParameters = false;
1126
    if (initialLoadFailures) {
1127
        _missingParameters = true;
1128 1129
        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. "
1130
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1131
                              "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());
1132
        qCDebug(ParameterManagerLog) << errorMsg;
1133
        qgcApp()->showAppMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
1134
        if (!qgcApp()->runningUnitTests()) {
1135
            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
1136
        }
1137 1138
    }

1139
    // Signal load complete
1140
    _parametersReady = true;
1141 1142 1143
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1144
}
1145

1146
void ParameterManager::_initialRequestTimeout(void)
1147
{
1148
    if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
1149
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Retrying initial parameter request list";
1150 1151
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
1152 1153
    } else {
        if (!_vehicle->genericFirmware()) {
Don Gagne's avatar
Don Gagne committed
1154
            QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1155
                                  "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(qgcApp()->applicationName());
1156
            qCDebug(ParameterManagerLog) << errorMsg;
1157
            qgcApp()->showAppMessage(errorMsg);
1158
        }
1159
    }
1160
}
1161

1162
/// Remap a parameter from one firmware version to another
1163
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174
{
    QString mappedParamName;

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

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

1175
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187

    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
1188
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1189 1190 1191 1192 1193
        return mappedParamName;
    }

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

1194
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1195 1196 1197 1198 1199 1200 1201

    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];
1202
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1203 1204 1205 1206 1207 1208 1209
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1210 1211

/// The offline editing vehicle can have custom loaded params bolted into it.
1212
void ParameterManager::_loadOfflineEditingParams(void)
1213
{
1214 1215 1216 1217 1218 1219 1220
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1221
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235
    }

    QTextStream paramStream(&paramFile);

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

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

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

1236 1237
        int defaultComponentId = paramData.at(1).toInt();
        _vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270
        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;
        }

1271 1272 1273 1274
        Fact* fact = new Fact(defaultComponentId, paramName, mavTypeToFactType(paramType), this);

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

1276
        _mapCompId2FactMap[defaultComponentId][paramName] = fact;
1277 1278 1279 1280
    }

    _parametersReady = true;
    _initialLoadComplete = true;
1281
    _debugCacheCRC.clear();
1282
}
1283

1284
void ParameterManager::resetAllParametersToDefaults()
1285
{
1286
    _vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1,
1287 1288 1289 1290
                             MAV_CMD_PREFLIGHT_STORAGE,
                             true,  // showError
                             2,     // Reset params to default
                             -1);   // Don't do anything with mission storage
1291 1292
}

1293 1294 1295 1296 1297 1298 1299 1300 1301
void ParameterManager::resetAllToVehicleConfiguration()
{
    //-- https://github.com/PX4/Firmware/pull/11760
    Fact* sysAutoConfigFact = getParameter(-1, "SYS_AUTOCONFIG");
    if(sysAutoConfigFact) {
        sysAutoConfigFact->setRawValue(2);
    }
}

1302 1303 1304 1305 1306 1307 1308 1309
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);
    }
}
1310 1311 1312

void ParameterManager::_setLoadProgress(double loadProgress)
{
1313 1314 1315 1316
    if (_loadProgress != loadProgress) {
        _loadProgress = loadProgress;
        emit loadProgressChanged(static_cast<float>(loadProgress));
    }
1317
}
Don Gagne's avatar
Don Gagne committed
1318 1319 1320 1321 1322

QList<int> ParameterManager::componentIds(void)
{
    return _paramCountMap.keys();
}
1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333

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

    return false;
}