ParameterManager.cc 60 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

10 11 12 13

/// @file
///     @author Don Gagne <don@thegagnes.com>

14
#include "ParameterManager.h"
15 16
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
17
#include "QGCApplication.h"
18
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
19
#include "FirmwarePlugin.h"
20
#include "UAS.h"
21
#include "JsonHelper.h"
22

23
#include <QEasingCurve>
24 25
#include <QFile>
#include <QDebug>
26
#include <QVariantAnimation>
27
#include <QJsonArray>
28

29 30 31 32 33
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;

34 35
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
36

37
Fact ParameterManager::_defaultFact;
Don Gagne's avatar
Don Gagne committed
38

39 40 41 42 43
const char* ParameterManager::_cachedMetaDataFilePrefix =   "ParameterFactMetaData";
const char* ParameterManager::_jsonParametersKey =          "parameters";
const char* ParameterManager::_jsonCompIdKey =              "compId";
const char* ParameterManager::_jsonParamNameKey =           "name";
const char* ParameterManager::_jsonParamValueKey =          "value";
44

45
ParameterManager::ParameterManager(Vehicle* vehicle)
46
    : QObject(vehicle)
47
    , _vehicle(vehicle)
48
    , _mavlink(NULL)
49
    , _loadProgress(0.0)
50
    , _parametersReady(false)
51
    , _missingParameters(false)
52
    , _initialLoadComplete(false)
53
    , _waitingForDefaultComponent(false)
54
    , _saveRequired(false)
Don Gagne's avatar
Don Gagne committed
55
    , _logReplay(vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay())
56 57
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
Don Gagne's avatar
Don Gagne committed
58 59 60
    , _prevWaitingReadParamIndexCount(0)
    , _prevWaitingReadParamNameCount(0)
    , _prevWaitingWriteParamNameCount(0)
61
    , _initialRequestRetryCount(0)
62
    , _disableAllRetries(false)
63
    , _indexBatchQueueActive(false)
64
    , _totalParamCount(0)
65
{
66 67
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

68 69 70 71 72 73
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

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

75
    _initialRequestTimeoutTimer.setSingleShot(true);
76
    _initialRequestTimeoutTimer.setInterval(5000);
77
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
78

79
    _waitingParamTimeoutTimer.setSingleShot(true);
80
    _waitingParamTimeoutTimer.setInterval(3000);
81
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
82

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

85 86
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
Don Gagne's avatar
Don Gagne committed
87

88
    refreshAllParameters();
89 90
}

91
ParameterManager::~ParameterManager()
92
{
93
    delete _parameterMetaData;
94 95 96
}

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

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

113 114
    // 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.
115
    if (parameterId == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
Patrick José Pereira's avatar
Patrick José Pereira committed
116
        qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to initial list response" << parameterName;
117 118 119
        return;
    }

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

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

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

Don Gagne's avatar
Don Gagne committed
140
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK" && !_logReplay) {
141
        /* we received a cache hash, potentially load from cache */
142
        _tryCacheHashLoad(vehicleId, componentId, value);
143 144
        return;
    }
145

146
    _initialRequestTimeoutTimer.stop();
147
    _waitingParamTimeoutTimer.stop();
148

149
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
150

151 152 153 154 155
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
156 157

    _mapParameterId2Name[componentId][parameterId] = parameterName;
dogmaphobic's avatar
dogmaphobic committed
158

159 160
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
161 162 163 164
        // 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;
165
        }
dogmaphobic's avatar
dogmaphobic committed
166

167 168 169
        // 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
170

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

174 175 176 177 178 179
    bool componentParamsComplete = false;
    if (_waitingReadParamIndexMap[componentId].count() == 1) {
        // We need to know when we get the last param from a component in order to complete setup
        componentParamsComplete = true;
    }

180 181 182
    if (!_waitingReadParamIndexMap[componentId].contains(parameterId) &&
        !_waitingReadParamNameMap[componentId].contains(parameterName) &&
        !_waitingWriteParamNameMap[componentId].contains(parameterName)) {
183
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName;
184 185
    }

186
    // Remove this parameter from the waiting lists
187 188 189 190 191
    if (_waitingReadParamIndexMap[componentId].contains(parameterId)) {
        _waitingReadParamIndexMap[componentId].remove(parameterId);
        _indexBatchQueue.removeOne(parameterId);
        _fillIndexBatchQueue(false /* waitingParamTimeout */);
    }
192 193
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
194 195 196 197 198 199 200 201 202
    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];
    }
203 204

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

206 207 208
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
209

210 211 212 213
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
214
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
215 216 217 218 219 220
    }

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

224 225 226 227
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
228
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
229
    }
dogmaphobic's avatar
dogmaphobic committed
230

Don Gagne's avatar
Don Gagne committed
231 232 233
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
234 235 236 237
        // More params to wait for, restart timer
        _waitingParamTimeoutTimer.start();
        qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
    } else {
238 239 240 241 242 243 244
        if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
            // Still waiting for parameters from default component
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
            _waitingParamTimeoutTimer.start();
        } else {
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
        }
245 246
    }

Don Gagne's avatar
Don Gagne committed
247 248 249 250 251
    // Update progress bar for waiting reads
    if (readWaitingParamCount == 0) {
        // We are no longer waiting for any reads to complete
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0) {
            // Set progress to 0 if not already there
252
            _setLoadProgress(0.0);
Don Gagne's avatar
Don Gagne committed
253
        }
254
    } else {
255
        _setLoadProgress((double)(_totalParamCount - readWaitingParamCount) / (double)_totalParamCount);
256
    }
dogmaphobic's avatar
dogmaphobic committed
257

258 259 260 261 262
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

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

266 267 268 269 270 271
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
272
                factType = FactMetaData::valueTypeInt8;
273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296
                break;
            case MAV_PARAM_TYPE_UINT16:
                factType = FactMetaData::valueTypeUint16;
                break;
            case MAV_PARAM_TYPE_INT16:
                factType = FactMetaData::valueTypeInt16;
                break;
            case MAV_PARAM_TYPE_UINT32:
                factType = FactMetaData::valueTypeUint32;
                break;
            case MAV_PARAM_TYPE_INT32:
                factType = FactMetaData::valueTypeInt32;
                break;
            case MAV_PARAM_TYPE_REAL32:
                factType = FactMetaData::valueTypeFloat;
                break;
            case MAV_PARAM_TYPE_REAL64:
                factType = FactMetaData::valueTypeDouble;
                break;
            default:
                factType = FactMetaData::valueTypeInt32;
                qCritical() << "Unsupported fact type" << mavType;
                break;
        }
dogmaphobic's avatar
dogmaphobic committed
297

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

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

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

Don Gagne's avatar
Don Gagne committed
306 307
    _dataMutex.unlock();

DonLakeFlyer's avatar
DonLakeFlyer committed
308 309 310 311 312 313 314 315 316
    Fact* fact = NULL;
    if (_mapParameterName2Variant[componentId].contains(parameterName)) {
        fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    }
    if (fact) {
        fact->_containerSetRawValue(value);
    } else {
        qWarning() << "Internal error";
    }
dogmaphobic's avatar
dogmaphobic committed
317

318
    if (componentParamsComplete) {
319
        if (componentId == _vehicle->defaultComponentId()) {
320 321 322 323 324 325 326 327 328 329 330
            // Add meta data to default component. We need to do this before we setup the group map since group
            // map requires meta data.
            _addMetaDataToDefaultComponent();
        }

        // When we are getting the very last component param index, reset the group maps to update for the
        // new params. By handling this here, we can pick up components which finish up later than the default
        // component param set.
        _setupGroupMap();
    }

Don Gagne's avatar
Don Gagne committed
331 332
    if (_prevWaitingWriteParamNameCount != 0 &&  waitingWriteParamNameCount == 0) {
        // If all the writes just finished the vehicle is up to date, so persist.
333 334
        _saveToEEPROM();
    }
dogmaphobic's avatar
dogmaphobic committed
335

Don Gagne's avatar
Don Gagne committed
336 337 338 339 340 341
    // 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.
    if (_vehicle->px4Firmware()) {
        if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
            // All reads just finished, update the cache
342
            _writeLocalParamCache(vehicleId, componentId);
Don Gagne's avatar
Don Gagne committed
343 344 345 346 347 348 349
        }
    }

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

350
    _checkInitialLoadComplete();
351 352

    qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
353 354 355 356
}

/// Connected to Fact::valueUpdated
///
357
/// Writes the parameter to mavlink, sets up for write wait
358
void ParameterManager::_valueUpdated(const QVariant& value)
359 360
{
    Fact* fact = qobject_cast<Fact*>(sender());
DonLakeFlyer's avatar
DonLakeFlyer committed
361 362 363 364
    if (!fact) {
        qWarning() << "Internal error";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
365

366
    int componentId = fact->componentId();
367
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
368

369
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
370

DonLakeFlyer's avatar
DonLakeFlyer committed
371 372 373 374 375 376 377 378
    if (_waitingWriteParamNameMap.contains(componentId)) {
        _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
        _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
        _waitingParamTimeoutTimer.start();
        _saveRequired = true;
    } else {
        qWarning() << "Internal error";
    }
dogmaphobic's avatar
dogmaphobic committed
379

380
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
381

382
    _writeParameterRaw(componentId, fact->name(), value);
383
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
384

385
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
386
        qgcApp()->showMessage(tr("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
387
    }
388 389
}

390
void ParameterManager::refreshAllParameters(uint8_t componentId)
391
{
Don Gagne's avatar
Don Gagne committed
392 393 394 395
    if (_logReplay) {
        return;
    }

396
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
397

398 399 400 401
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

402
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
403
    foreach (int cid, _paramCountMap.keys()) {
404
        // Add/Update all indices to the wait list, parameter index is 0-based
405
        if(componentId != MAV_COMP_ID_ALL && componentId != cid)
dogmaphobic's avatar
dogmaphobic committed
406 407
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
408
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
409
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
410 411
        }
    }
dogmaphobic's avatar
dogmaphobic committed
412

413
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
414

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

417
    mavlink_message_t msg;
418 419 420 421 422
    mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(),
                                             mavlink->getComponentId(),
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,
                                             _vehicle->id(),
423
                                             componentId);
424
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
425

426 427
    QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what;
428 429 430
}

/// Translates FactSystem::defaultComponentId to real component id if needed
431
int ParameterManager::_actualComponentId(int componentId)
432 433
{
    if (componentId == FactSystem::defaultComponentId) {
434
        componentId = _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
435
        if (componentId == FactSystem::defaultComponentId) {
436
            qWarning() << _logVehiclePrefix() << "Default component id not set";
Don Gagne's avatar
Don Gagne committed
437
        }
438
    }
dogmaphobic's avatar
dogmaphobic committed
439

440 441 442
    return componentId;
}

443
void ParameterManager::refreshParameter(int componentId, const QString& name)
444
{
445
    componentId = _actualComponentId(componentId);
446
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
447

448 449 450
    _dataMutex.lock();

    if (_waitingReadParamNameMap.contains(componentId)) {
451 452 453 454
        QString mappedParamName = _remapParamNameToVersion(name);

        _waitingReadParamNameMap[componentId].remove(mappedParamName);  // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][mappedParamName] = 0;     // Add new wait entry and update retry count
455 456
        qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
        _waitingParamTimeoutTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
457 458
    } else {
        qWarning() << "Internal error";
459
    }
dogmaphobic's avatar
dogmaphobic committed
460

461 462 463
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
464 465
}

466
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
467 468
{
    componentId = _actualComponentId(componentId);
469
    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
470

471
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
472 473 474 475 476 477
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

478
bool ParameterManager::parameterExists(int componentId, const QString&  name)
479
{
480
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
481

482 483
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
484
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
485
    }
486 487

    return ret;
488 489
}

490
Fact* ParameterManager::getParameter(int componentId, const QString& name)
491 492
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
493

494 495 496
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
497
        return &_defaultFact;
498
    }
dogmaphobic's avatar
dogmaphobic committed
499

500
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
501
}
502

503
QStringList ParameterManager::parameterNames(int componentId)
504
{
dogmaphobic's avatar
dogmaphobic committed
505 506
    QStringList names;

507
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
508 509 510 511
        names << paramName;
    }

    return names;
512 513
}

514
void ParameterManager::_setupGroupMap(void)
515
{
516 517 518
    // Must be able to handle being called multiple times
    _mapGroup2ParameterName.clear();

519
    foreach (int componentId, _mapParameterName2Variant.keys()) {
520
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
521 522 523 524 525 526
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

527
const QMap<int, QMap<QString, QStringList> >& ParameterManager::getGroupMap(void)
528 529 530
{
    return _mapGroup2ParameterName;
}
531

532 533 534 535
/// 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)
536
{
537 538 539
    if (!_indexBatchQueueActive) {
        return false;
    }
dogmaphobic's avatar
dogmaphobic committed
540

541
    const int maxBatchSize = 10;
542

543 544 545 546 547 548 549
    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";
    }
550

551
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
552
        if (_waitingReadParamIndexMap[componentId].count()) {
553 554
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
            qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
555 556
        }

557 558 559 560 561 562 563 564
        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
            if (_indexBatchQueue.contains(paramIndex)) {
                // Don't add more than once
                continue;
            }

            if (_indexBatchQueue.count() > maxBatchSize) {
                break;
565 566
            }

567
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
568
            if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
569 570
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
571
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
572 573 574
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
575
                _indexBatchQueue.append(paramIndex);
576
                _readParameterRaw(componentId, "", paramIndex);
577
                qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
578 579 580
            }
        }
    }
581

582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598
    return _indexBatchQueue.count() != 0;
}

void ParameterManager::_waitingParamTimeout(void)
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;

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

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

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

599 600 601
    if (!paramsRequested && !_waitingForDefaultComponent && !_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
        // Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the
        // any show up.
602
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys();
603 604 605 606 607 608
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

609
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
610

611 612
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
613
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
614
                paramsRequested = true;
615
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
616
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
617
                    _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
618
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
619
                    if (++batchCount > maxBatchSize) {
620 621 622 623 624
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingWriteParamNameMap[componentId].remove(paramName);
625 626 627
                    QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
                    qgcApp()->showMessage(errorMsg);
628 629 630 631
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
632

633 634
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
635
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
636
                paramsRequested = true;
637
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
638 639
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
640
                    qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
641
                    if (++batchCount > maxBatchSize) {
642 643 644 645 646
                        goto Out;
                    }
                } else {
                    // Exceeded max retry count, notify user
                    _waitingReadParamNameMap[componentId].remove(paramName);
647 648 649
                    QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
                    qCDebug(ParameterManagerLog) << errorMsg;
                    qgcApp()->showMessage(errorMsg);
650 651 652 653
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
654

655 656
Out:
    if (paramsRequested) {
657
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request";
658 659 660 661
        _waitingParamTimeoutTimer.start();
    }
}

662
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
663 664 665 666 667
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
668 669 670 671 672 673 674 675
    mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(),   // QGC system id
                                             _mavlink->getComponentId(),     // QGC component id
                                             _vehicle->priorityLink()->mavlinkChannel(),
                                             &msg,                           // Pack into this mavlink_message_t
                                             _vehicle->id(),                 // Target system id
                                             componentId,                    // Target component id
                                             fixedParamName,                 // Named parameter being requested
                                             paramIndex);                    // Parameter index being requested, -1 for named
676
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
677 678
}

679
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
680 681 682
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
683

Don Gagne's avatar
Don Gagne committed
684 685
    memset(&p, 0, sizeof(p));

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

689 690
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
691
            union_value.param_uint8 = (uint8_t)value.toUInt();
692
            break;
dogmaphobic's avatar
dogmaphobic committed
693

694
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
695
            union_value.param_int8 = (int8_t)value.toInt();
696
            break;
dogmaphobic's avatar
dogmaphobic committed
697

698
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
699
            union_value.param_uint16 = (uint16_t)value.toUInt();
700
            break;
dogmaphobic's avatar
dogmaphobic committed
701

702
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
703
            union_value.param_int16 = (int16_t)value.toInt();
704
            break;
dogmaphobic's avatar
dogmaphobic committed
705

706
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
707
            union_value.param_uint32 = (uint32_t)value.toUInt();
708
            break;
dogmaphobic's avatar
dogmaphobic committed
709

710 711 712
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
713

714 715 716
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
717

718
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
719
            union_value.param_int32 = (int32_t)value.toInt();
720 721
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
722

723
    p.param_value = union_value.param_float;
724
    p.target_system = (uint8_t)_vehicle->id();
725
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
726

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

729
    mavlink_message_t msg;
730 731 732 733 734
    mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                      _mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      &p);
735
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
736 737
}

738
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
739
{
740
    MapID2NamedParam cache_map;
741

742 743 744 745
    foreach(int id, _mapParameterId2Name[componentId].keys()) {
        const QString name(_mapParameterId2Name[componentId][id]);
        const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
        cache_map[id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue()));
746 747
    }

748
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
749 750 751 752 753 754
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

    QDataStream ds(&cache_file);
    ds << cache_map;
}

755
QDir ParameterManager::parameterCacheDir()
756 757 758 759 760
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

761
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
762
{
763
    return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId));
764 765
}

766
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
767 768 769
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
770
    MapID2NamedParam cache_map;
771
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
772
    if (!cache_file.exists()) {
773
        /* no local cache, just wait for them to come in*/
774 775 776 777 778 779 780 781 782
        return;
    }
    cache_file.open(QIODevice::ReadOnly);

    /* Deserialize the parameter cache table */
    QDataStream ds(&cache_file);
    ds >> cache_map;

    /* compute the crc of the local cache to check against the remote */
783 784 785 786 787 788 789

    foreach(int id, cache_map.keys()) {
        const QString name(cache_map[id].first);
        const void *vdat = cache_map[id].second.second.constData();
        const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.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);
790 791 792
    }

    if (crc32_value == hash_value.toUInt()) {
793
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
794
        /* if the two param set hashes match, just load from the disk */
795 796 797 798 799 800
        int count = cache_map.count();
        foreach(int id, cache_map.keys()) {
            const QString &name = cache_map[id].first;
            const QVariant &value = cache_map[id].second.second;
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first);
            const int mavType = _factTypeToMavType(fact_type);
801
            _parameterUpdate(vehicleId, componentId, name, count, id, mavType, value);
802
        }
803 804 805
        // 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
806
        memset(&p, 0, sizeof(p));
807 808 809 810 811 812 813
        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;
814 815 816 817 818
        mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(),
                                          _mavlink->getComponentId(),
                                          _vehicle->priorityLink()->mavlinkChannel(),
                                          &msg,
                                          &p);
819
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
820 821 822 823 824 825 826 827 828

        // Give the user some feedback things loaded properly
        QVariantAnimation *ani = new QVariantAnimation(this);
        ani->setEasingCurve(QEasingCurve::OutCubic);
        ani->setStartValue(0.0);
        ani->setEndValue(1.0);
        ani->setDuration(750);

        connect(ani, &QVariantAnimation::valueChanged, [this](const QVariant &value) {
829
            _setLoadProgress(value.toDouble());
830 831 832 833 834
        });

        // Hide 500ms after animation finishes
        connect(ani, &QVariantAnimation::finished, [this](){
            QTimer::singleShot(500, [this]() {
835
                _setLoadProgress(0);
836 837 838 839
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
DonLakeFlyer's avatar
DonLakeFlyer committed
840 841
    } else {
        qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
842 843 844
    }
}

845
void ParameterManager::_saveToEEPROM(void)
846
{
847 848
    if (_saveRequired) {
        _saveRequired = false;
849
        if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
850 851 852 853 854
            _vehicle->sendMavCommand(MAV_COMP_ID_ALL,
                                     MAV_CMD_PREFLIGHT_STORAGE,
                                     true,  // showError
                                     1,     // Write parameters to EEPROM
                                     -1);   // Don't do anything with mission storage
855
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM";
856
        } else {
857
            qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
858
        }
Don Gagne's avatar
Don Gagne committed
859
    }
860 861
}

862
QString ParameterManager::readParametersFromStream(QTextStream& stream)
863
{
864
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
865

866 867 868 869 870 871
    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
872 873
                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
874 875
                }

876 877 878 879
                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
880

881
                if (!parameterExists(componentId, paramName)) {
882 883 884
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
885
                    qCDebug(ParameterManagerLog) << error;
886 887
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
888

889
                Fact* fact = getParameter(componentId, paramName);
890
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
891 892 893
                    QString error;
                    error  = QString("Skipped parameter %1:%2 - type mismatch %3:%4\n").arg(componentId).arg(paramName).arg(fact->type()).arg(_mavTypeToFactType((MAV_PARAM_TYPE)mavType));
                    errors += error;
894
                    qCDebug(ParameterManagerLog) << error;
895 896
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
897

898
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
899
                fact->setRawValue(valStr);
900 901 902
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
903

904
    return errors;
905 906
}

907
void ParameterManager::writeParametersToStream(QTextStream &stream)
908
{
Don Gagne's avatar
Don Gagne committed
909
    stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
910 911 912 913 914 915 916 917 918 919 920
    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";

921
    stream << "#\n";
Don Gagne's avatar
Don Gagne committed
922
    stream << "# Vehicle-Id Component-Id Name Value Type\n";
923 924

    foreach (int componentId, _mapParameterName2Variant.keys()) {
925
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
926
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
927 928 929 930 931
            if (fact) {
                stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
            } else {
                qWarning() << "Internal error: missing fact";
            }
932 933
        }
    }
dogmaphobic's avatar
dogmaphobic committed
934

935 936 937
    stream.flush();
}

938
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
939 940 941 942
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
943

944 945
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
946

947 948
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
949

950 951
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
952

953 954
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
955

956 957
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
958

959 960 961
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
962

963 964 965 966 967
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

968
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
969 970 971 972
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
973

974 975
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
976

977 978
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
979

980 981
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
982

983 984
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
985

986 987
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
988

989 990 991
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
992

993 994 995 996 997
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

998
void ParameterManager::_addMetaDataToDefaultComponent(void)
999 1000 1001 1002 1003
{
     if (_parameterMetaData) {
         return;
     }

Don Gagne's avatar
Don Gagne committed
1004
     QString metaDataFile;
1005
     int majorVersion, minorVersion;
1006 1007 1008 1009

     // Load best parameter meta data set
     metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
     qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
Don Gagne's avatar
Don Gagne committed
1010

1011 1012 1013
     _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);

    // Loop over all parameters in default component adding meta data
1014
    QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()];
1015 1016 1017 1018 1019
    foreach (const QString& key, factMap.keys()) {
        _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value<Fact*>(), _vehicle->vehicleType());
    }
}

1020
void ParameterManager::_checkInitialLoadComplete(void)
1021 1022 1023 1024 1025
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
1026

1027 1028 1029 1030 1031 1032
    foreach (int componentId, _waitingReadParamIndexMap.keys()) {
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
1033

1034 1035 1036 1037 1038
    if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) {
        // No default component params yet, not done yet
        return;
    }

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

1042 1043
    qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";

1044 1045 1046 1047 1048 1049 1050 1051 1052 1053
    // Check for index based load failures
    QString indexList;
    bool initialLoadFailures = false;
    foreach (int componentId, _failedReadParamIndexMap.keys()) {
        foreach (int paramIndex, _failedReadParamIndexMap[componentId]) {
            if (initialLoadFailures) {
                indexList += ", ";
            }
            indexList += QString("%1").arg(paramIndex);
            initialLoadFailures = true;
1054
            qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1055 1056
        }
    }
1057 1058

    _missingParameters = false;
1059
    if (initialLoadFailures) {
1060
        _missingParameters = true;
1061 1062
        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. "
1063
                              "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1064
                              "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());
1065 1066
        qCDebug(ParameterManagerLog) << errorMsg;
        qgcApp()->showMessage(errorMsg);
Don Gagne's avatar
Don Gagne committed
1067
        if (!qgcApp()->runningUnitTests()) {
1068
            qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
Don Gagne's avatar
Don Gagne committed
1069
        }
1070 1071
    }

1072
    // Signal load complete
1073
    _parametersReady = true;
1074 1075 1076
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1077
}
1078

1079
void ParameterManager::_initialRequestTimeout(void)
1080
{
1081
    if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
1082
        qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retrying initial parameter request list";
1083 1084
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
1085 1086
    } else {
        if (!_vehicle->genericFirmware()) {
Don Gagne's avatar
Don Gagne committed
1087
            QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1088
                                  "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(qgcApp()->applicationName());
1089 1090 1091
            qCDebug(ParameterManagerLog) << errorMsg;
            qgcApp()->showMessage(errorMsg);
        }
1092
    }
1093
}
1094

1095
QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111
{
    bool            cacheHit = false;
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    // Cached files are stored in settings location
    QSettings settings;
    QDir cacheDir = QFileInfo(settings.fileName()).dir();

    // First look for a direct cache hit
    int cacheMinorVersion, cacheMajorVersion;
    QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion)));
    if (cacheFile.exists()) {
        plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion);
        if (wantedMajorVersion != cacheMajorVersion) {
            qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
        } else {
1112
            qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144
            cacheHit = true;
        }
    }

    if (!cacheHit) {
        // No direct hit, look for lower param set version
        QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType);
        QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name);

        // Find the highest major version number which is below the vehicles major version number
        int cacheHitIndex = -1;
        cacheMajorVersion = -1;
        QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType));
        for (int i=0; i< cacheHits.count(); i++) {
            if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) {
                int majorVersion = regExp.capturedTexts()[0].toInt();
                if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) {
                    cacheMajorVersion = majorVersion;
                    cacheHitIndex = i;
                }
            }
        }

        if (cacheHitIndex != -1) {
            // We have a cache hit on a lower major version, read minor version as well
            int majorVersion;
            cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex]));
            plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion);
            if (majorVersion != cacheMajorVersion) {
                qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
                cacheHit = false;
            } else {
1145
                qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
1146 1147 1148 1149 1150 1151
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
1152
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile(vehicle);
1153
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
1154
    qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185
    if (cacheHit) {
        // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
        if (internalMajorVersion == wantedMajorVersion) {
            if (cacheMajorVersion == wantedMajorVersion) {
                // Both internal and cache are direct hit on major version, Use higher minor version number
                cacheHit = cacheMinorVersion > internalMinorVersion;
            } else {
                // Direct internal hit, but not direct hit in cache, use internal
                cacheHit = false;
            }
        } else {
            if (cacheMajorVersion == wantedMajorVersion) {
                // Direct hit on cache, no direct hit on internal, use cache
                cacheHit = true;
            } else {
                // No direct hit anywhere, use internal
                cacheHit = false;
            }
        }
    }

    QString metaDataFile;
    if (cacheHit && !qgcApp()->runningUnitTests()) {
        majorVersion = cacheMajorVersion;
        minorVersion = cacheMinorVersion;
        metaDataFile = cacheFile.fileName();
    } else {
        majorVersion = internalMajorVersion;
        minorVersion = internalMinorVersion;
        metaDataFile = internalMetaDataFile;
    }
1186
    qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
1187 1188 1189 1190

    return metaDataFile;
}

1191
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
1192 1193 1194 1195 1196
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
1197
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
1198 1199 1200

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
1201
    QString cacheHit = ParameterManager::parameterMetaDataFile(NULL, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
1202
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226

    bool cacheNewFile = false;
    if (cacheHit.isEmpty()) {
        // No cache hits, store the new file
        cacheNewFile = true;
    } else if (cacheMajorVersion == newMajorVersion) {
        // Direct hit on major version in cache:
        //      Cache new file if newer minor version
        //      Also delete older cache file
        if (newMinorVersion > cacheMinorVersion) {
            cacheNewFile = true;
            QFile::remove(cacheHit);
        }
    } else {
        // Indirect hit in cache, store new file
        cacheNewFile = true;
    }

    if (cacheNewFile) {
        // Cached files are stored in settings location. Copy from current file to cache naming.

        QSettings settings;
        QDir cacheDir = QFileInfo(settings.fileName()).dir();
        QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(newMajorVersion)));
1227
        qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
1228 1229 1230 1231
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1232 1233

/// Remap a parameter from one firmware version to another
1234
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245
{
    QString mappedParamName;

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

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

1246
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258

    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
1259
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1260 1261 1262 1263 1264
        return mappedParamName;
    }

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

1265
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1266 1267 1268 1269 1270 1271 1272

    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];
1273
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1274 1275 1276 1277 1278 1279 1280
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1281 1282

/// The offline editing vehicle can have custom loaded params bolted into it.
1283
void ParameterManager::_loadOfflineEditingParams(void)
1284 1285 1286 1287 1288 1289 1290 1291
{    
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1292
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306
    }

    QTextStream paramStream(&paramFile);

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

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

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

1307 1308
        int defaultComponentId = paramData.at(1).toInt();
        _vehicle->setOfflineEditingDefaultComponentId(defaultComponentId);
1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341
        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;
        }

1342 1343 1344 1345 1346
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1347 1348
        Fact* fact = new Fact(defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact);
1349 1350 1351
    }

    _addMetaDataToDefaultComponent();
1352
    _setupGroupMap();
1353 1354 1355
    _parametersReady = true;
    _initialLoadComplete = true;
}
1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395

void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject)
{
    QList<int>  rgCompIds;
    QStringList rgParamNames;

    if (componentId == MAV_COMP_ID_ALL) {
        rgCompIds = _mapParameterName2Variant.keys();
    } else {
        rgCompIds.append(_actualComponentId(componentId));
    }

    QJsonArray rgParams;

    // Loop over all requested component ids
    for (int i=0; i<rgCompIds.count(); i++) {
        int compId = rgCompIds[i];

        if (!_mapParameterName2Variant.contains(compId)) {
            qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson no params for compId" << compId;
            continue;
        }

        // Build list of parameter names if not specified
        if (paramsToSave.count() == 0) {
            rgParamNames = 	parameterNames(compId);
        } else {
            rgParamNames = paramsToSave;
        }

        // Loop over parameter names adding each to json array
        for (int j=0; j<rgParamNames.count(); j++) {
            QString paramName = rgParamNames[j];

            if (!parameterExists(compId, paramName)) {
                qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson param not found compId:param" << compId << paramName;
                continue;
            }

            QJsonObject paramJson;
1396
            Fact* fact = getParameter(compId, paramName);
1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454
            paramJson.insert(_jsonCompIdKey, QJsonValue(compId));
            paramJson.insert(_jsonParamNameKey, QJsonValue(fact->name()));
            paramJson.insert(_jsonParamValueKey, QJsonValue(fact->rawValue().toDouble()));

            rgParams.append(QJsonValue(paramJson));
        }
    }

    saveObject.insert(_jsonParametersKey, QJsonValue(rgParams));
}

bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
{
    QList<QJsonValue::Type> keyTypes;

    errorString.clear();

    if (required) {
        if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonParametersKey), errorString)) {
            return false;
        }
    } else if (!json.contains(_jsonParametersKey)) {
        return true;
    }

    keyTypes = { QJsonValue::Array };
    if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonParametersKey), keyTypes, errorString)) {
        return false;
    }

    QJsonArray rgParams = json[_jsonParametersKey].toArray();
    for (int i=0; i<rgParams.count(); i++) {
        QJsonValueRef paramValue = rgParams[i];

        if (!paramValue.isObject()) {
            errorString = tr("%1 key is not a json object").arg(_jsonParametersKey);
            return false;
        }
        QJsonObject param = paramValue.toObject();

        QStringList requiredKeys = { _jsonCompIdKey, _jsonParamNameKey, _jsonParamValueKey };
        if (!JsonHelper::validateRequiredKeys(param, requiredKeys, errorString)) {
            return false;
        }
        keyTypes = { QJsonValue::Double, QJsonValue::String, QJsonValue::Double };
        if (!JsonHelper::validateKeyTypes(param, requiredKeys, keyTypes, errorString)) {
            return false;
        }

        int compId = param[_jsonCompIdKey].toInt();
        QString name = param[_jsonParamNameKey].toString();
        double value = param[_jsonParamValueKey].toDouble();

        if (!parameterExists(compId, name)) {
            qCDebug(ParameterManagerLog) << "ParameterManager::loadFromJson param not found compId:param" << compId << name;
            continue;
        }

1455
        Fact* fact = getParameter(compId, name);
1456 1457 1458 1459 1460 1461
        fact->setRawValue(value);
    }

    return true;
}

1462 1463
void ParameterManager::resetAllParametersToDefaults(void)
{
1464 1465 1466 1467 1468
    _vehicle->sendMavCommand(MAV_COMP_ID_ALL,
                             MAV_CMD_PREFLIGHT_STORAGE,
                             true,  // showError
                             2,     // Reset params to default
                             -1);   // Don't do anything with mission storage
1469 1470
}

1471 1472 1473 1474 1475 1476 1477 1478
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);
    }
}
1479 1480 1481 1482 1483 1484

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