ParameterLoader.cc 32.9 KB
Newer Older
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
dogmaphobic's avatar
dogmaphobic committed
13

14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
dogmaphobic's avatar
dogmaphobic committed
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

22 23 24 25 26 27 28 29
 ======================================================================*/

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

#include "ParameterLoader.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
30
#include "QGCApplication.h"
31
#include "QGCMessageBox.h"
32
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
33
#include "FirmwarePlugin.h"
34
#include "UAS.h"
35 36 37 38

#include <QFile>
#include <QDebug>

39 40 41 42 43
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;

44
QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
45
QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
46

Don Gagne's avatar
Don Gagne committed
47 48
Fact ParameterLoader::_defaultFact;

49
ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
50
    QObject(parent),
51
    _autopilot(autopilot),
52
    _vehicle(vehicle),
53
    _mavlink(qgcApp()->toolbox()->mavlinkProtocol()),
54
    _parametersReady(false),
55
    _initialLoadComplete(false),
56
    _defaultComponentId(FactSystem::defaultComponentId),
57
    _totalParamCount(0)
58
{
59
    Q_ASSERT(_autopilot);
60
    Q_ASSERT(_vehicle);
61
    Q_ASSERT(_mavlink);
dogmaphobic's avatar
dogmaphobic committed
62

63 64
    // We signal this to ouselves in order to start timer on our thread
    connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
dogmaphobic's avatar
dogmaphobic committed
65

66
    _waitingParamTimeoutTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
67
    _waitingParamTimeoutTimer.setInterval(1000);
68
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
69 70 71 72

    _cacheTimeoutTimer.setSingleShot(true);
    _cacheTimeoutTimer.setInterval(2500);
    connect(&_cacheTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::refreshAllParameters);
dogmaphobic's avatar
dogmaphobic committed
73

74
    // FIXME: Why not direct connect?
75
    connect(_vehicle->uas(), SIGNAL(parameterUpdate(int, int, QString, int, int, int, QVariant)), this, SLOT(_parameterUpdate(int, int, QString, int, int, int, QVariant)));
76 77 78

    /* Initially attempt a local cache load, refresh over the link if it fails */
    _tryCacheLookup();
79 80 81 82 83 84 85 86
}

ParameterLoader::~ParameterLoader()
{

}

/// Called whenever a parameter is updated or first seen.
87
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
88 89
{
    bool setMetaData = false;
dogmaphobic's avatar
dogmaphobic committed
90

91
    // Is this for our uas?
92
    if (uasId != _vehicle->id()) {
93 94
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
95

96 97 98 99 100 101 102 103
    qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
                                    "componentId:" << componentId <<
                                    "name:" << parameterName <<
                                    "count:" << parameterCount <<
                                    "index:" << parameterId <<
                                    "mavType:" << mavType <<
                                    "value:" << value <<
                                    ")";
dogmaphobic's avatar
dogmaphobic committed
104

105 106 107 108 109 110 111 112
#if 0
    // Handy for testing retry logic
    static int counter = 0;
    if (counter++ & 0x3) {
        qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
        return;
    }
#endif
113 114 115 116 117 118 119

    if (parameterName == "_HASH_CHECK") {
        /* we received a cache hash, potentially load from cache */
        _cacheTimeoutTimer.stop();
        _tryCacheHashLoad(uasId, value);
        return;
    }
120
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
121

122 123
    // Restart our waiting for param timer
    _waitingParamTimeoutTimer.start();
dogmaphobic's avatar
dogmaphobic committed
124

125 126 127 128 129
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
130 131

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

133 134
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
135 136 137 138
        // 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;
139
        }
dogmaphobic's avatar
dogmaphobic committed
140

141 142 143
        // 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
144

145 146
        qCDebug(ParameterLoaderLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
    }
dogmaphobic's avatar
dogmaphobic committed
147

148
    // Remove this parameter from the waiting lists
149 150 151
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
152
    qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
153 154 155 156
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

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

158 159 160
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
161

162 163 164 165 166 167 168
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

dogmaphobic's avatar
dogmaphobic committed
169

170 171 172 173 174 175
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
176

177 178 179 180 181 182
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
183

184 185 186 187 188 189 190 191 192 193 194 195 196 197
    int waitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount + waitingWriteParamNameCount;
    if (waitingParamCount) {
        qCDebug(ParameterLoaderLog) << "waitingParamCount:" << waitingParamCount;
    } else {
        // No more parameters to wait for, stop the timeout
        _waitingParamTimeoutTimer.stop();
    }

    // Update progress bar
    if (waitingParamCount == 0) {
        emit parameterListProgress(0);
    } else {
        emit parameterListProgress((float)(_totalParamCount - waitingParamCount) / (float)_totalParamCount);
    }
dogmaphobic's avatar
dogmaphobic committed
198

199 200
    // Attempt to determine default component id
    if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) {
201
        _defaultComponentIdParam = _vehicle->firmwarePlugin()->getDefaultComponentIdParam();
202 203 204 205
    }
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        _defaultComponentId = componentId;
    }
dogmaphobic's avatar
dogmaphobic committed
206

207
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
208
        qCDebug(ParameterLoaderLog) << "Adding new fact";
dogmaphobic's avatar
dogmaphobic committed
209

210 211 212 213 214 215
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
216
                factType = FactMetaData::valueTypeInt8;
217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240
                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
241

242 243
        Fact* fact = new Fact(componentId, parameterName, factType, this);
        setMetaData = true;
dogmaphobic's avatar
dogmaphobic committed
244

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

247 248 249
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
        connect(fact, &Fact::_containerValueChanged, this, &ParameterLoader::_valueUpdated);
    }
dogmaphobic's avatar
dogmaphobic committed
250

251
    Q_ASSERT(_mapParameterName2Variant[componentId].contains(parameterName));
dogmaphobic's avatar
dogmaphobic committed
252

253 254 255
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
    fact->_containerSetValue(value);
dogmaphobic's avatar
dogmaphobic committed
256

257
    if (setMetaData) {
258
        _vehicle->firmwarePlugin()->addMetaDataToFact(fact);
259
    }
dogmaphobic's avatar
dogmaphobic committed
260

261
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
262

263 264 265
    if (waitingParamCount == 0) {
        // Now that we know vehicle is up to date persist
        _saveToEEPROM();
266
        _writeLocalParamCache();
267
    }
dogmaphobic's avatar
dogmaphobic committed
268

269
    _checkInitialLoadComplete();
270 271 272 273
}

/// Connected to Fact::valueUpdated
///
274
/// Writes the parameter to mavlink, sets up for write wait
275 276 277 278
void ParameterLoader::_valueUpdated(const QVariant& value)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
279

280
    int componentId = fact->componentId();
281
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
282

283
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
284

285
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
286 287
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
288
    _waitingParamTimeoutTimer.start();
dogmaphobic's avatar
dogmaphobic committed
289

290
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
291

292 293
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
294 295 296 297
}

void ParameterLoader::refreshAllParameters(void)
{
298
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
299

300 301
    // Reset index wait lists
    foreach (int componentId, _paramCountMap.keys()) {
302 303 304 305
        // Add/Update all indices to the wait list, parameter index is 0-based
        for (int waitingIndex=0; waitingIndex<_paramCountMap[componentId]; waitingIndex++) {
            // This will add a new waiting index if needed and set the retry count for that index to 0
            _waitingReadParamIndexMap[componentId][waitingIndex] = 0;
306 307
        }
    }
dogmaphobic's avatar
dogmaphobic committed
308

309
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
310

311
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
312
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
313

314
    mavlink_message_t msg;
315 316
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL);
    _vehicle->sendMessage(msg);
dogmaphobic's avatar
dogmaphobic committed
317

318
    qCDebug(ParameterLoaderLog) << "Request to refresh all parameters";
319 320 321 322 323 324 325 326
}

void ParameterLoader::_determineDefaultComponentId(void)
{
    if (_defaultComponentId == FactSystem::defaultComponentId) {
        // We don't have a default component id yet. That means the plugin can't provide
        // the param to trigger off of. Instead we use the most prominent component id in
        // the set of parameters. Better than nothing!
dogmaphobic's avatar
dogmaphobic committed
327

328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344
        _defaultComponentId = -1;
        foreach(int componentId, _mapParameterName2Variant.keys()) {
            if (_mapParameterName2Variant[componentId].count() > _defaultComponentId) {
                _defaultComponentId = componentId;
            }
        }
        Q_ASSERT(_defaultComponentId != -1);
    }
}

/// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterLoader::_actualComponentId(int componentId)
{
    if (componentId == FactSystem::defaultComponentId) {
        componentId = _defaultComponentId;
        Q_ASSERT(componentId != FactSystem::defaultComponentId);
    }
dogmaphobic's avatar
dogmaphobic committed
345

346 347 348 349 350
    return componentId;
}

void ParameterLoader::refreshParameter(int componentId, const QString& name)
{
351 352
    componentId = _actualComponentId(componentId);
    qCDebug(ParameterLoaderLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
353

354 355 356
    _dataMutex.lock();

    Q_ASSERT(_waitingReadParamNameMap.contains(componentId));
dogmaphobic's avatar
dogmaphobic committed
357

358
    if (_waitingReadParamNameMap.contains(componentId)) {
359 360
        _waitingReadParamNameMap[componentId].remove(name); // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][name] = 0;    // Add new wait entry and update retry count
361 362
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
363

364 365 366
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
367 368 369 370 371
}

void ParameterLoader::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
    componentId = _actualComponentId(componentId);
372 373
    qCDebug(ParameterLoaderLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";

374 375 376 377 378 379 380
    foreach(QString name, _mapParameterName2Variant[componentId].keys()) {
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

381
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
382
{
383
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
384

385 386
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
387
        ret = _mapParameterName2Variant[componentId].contains(name);
388
    }
389 390

    return ret;
391 392 393 394 395
}

Fact* ParameterLoader::getFact(int componentId, const QString& name)
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
396

397
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) {
Don Gagne's avatar
Don Gagne committed
398 399
        qgcApp()->reportMissingParameter(componentId, name);
        return &_defaultFact;
400
    }
dogmaphobic's avatar
dogmaphobic committed
401

Don Gagne's avatar
Don Gagne committed
402
    return _mapParameterName2Variant[componentId][name].value<Fact*>();
403
}
404

Don Gagne's avatar
Don Gagne committed
405
QStringList ParameterLoader::parameterNames(int componentId)
406
{
dogmaphobic's avatar
dogmaphobic committed
407 408 409 410 411 412 413
    QStringList names;

    foreach(QString paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
        names << paramName;
    }

    return names;
414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429
}

void ParameterLoader::_setupGroupMap(void)
{
    foreach (int componentId, _mapParameterName2Variant.keys()) {
        foreach (QString name, _mapParameterName2Variant[componentId].keys()) {
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
430 431 432 433 434 435

void ParameterLoader::_waitingParamTimeout(void)
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
dogmaphobic's avatar
dogmaphobic committed
436

437
    // We timed out waiting for some parameters from the initial set. Re-request those.
dogmaphobic's avatar
dogmaphobic committed
438

439 440
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
441 442 443 444 445 446 447 448 449 450 451 452
        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
            if (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetry) {
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
                qCDebug(ParameterLoaderLog) << "Giving up on (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
                paramsRequested = true;
                _readParameterRaw(componentId, "", paramIndex);
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
dogmaphobic's avatar
dogmaphobic committed
453

454 455 456
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
457 458 459
            }
        }
    }
460 461
    // We need to check for initial load complete here as well, since it could complete on a max retry failure
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
462

463 464
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
465
            foreach(QString paramName, _waitingWriteParamNameMap[componentId].keys()) {
466
                paramsRequested = true;
467
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
468
                _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->value());
469
                qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
470

471 472 473 474 475 476
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
477

478 479
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
480
            foreach(QString paramName, _waitingReadParamNameMap[componentId].keys()) {
481
                paramsRequested = true;
482
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
483
                _readParameterRaw(componentId, paramName, -1);
484
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
485

486 487 488 489 490 491
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
492

493 494 495 496 497 498
Out:
    if (paramsRequested) {
        _waitingParamTimeoutTimer.start();
    }
}

499 500 501 502 503
void ParameterLoader::_tryCacheLookup()
{
    /* Start waiting for 2.5 seconds to get a cache hit and avoid loading all params over the radio */
    _cacheTimeoutTimer.start();

504
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
505 506 507 508 509 510 511
    Q_ASSERT(mavlink);

    mavlink_message_t msg;
    mavlink_msg_param_request_read_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL, "_HASH_CHECK", -1);
    _vehicle->sendMessage(msg);
}

512 513 514 515 516 517 518 519 520
void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
    mavlink_msg_param_request_read_pack(_mavlink->getSystemId(),    // Our system id
                                        _mavlink->getComponentId(), // Our component id
                                        &msg,                       // Pack into this mavlink_message_t
521
                                        _vehicle->id(),             // Target system id
522 523 524
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
525
    _vehicle->sendMessage(msg);
526 527 528 529 530 531
}

void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
532

533 534
    FactMetaData::ValueType_t factType = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
    p.param_type = _factTypeToMavType(factType);
dogmaphobic's avatar
dogmaphobic committed
535

536 537
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
538
            union_value.param_uint8 = (uint8_t)value.toUInt();
539
            break;
dogmaphobic's avatar
dogmaphobic committed
540

541
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
542
            union_value.param_int8 = (int8_t)value.toInt();
543
            break;
dogmaphobic's avatar
dogmaphobic committed
544

545
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
546
            union_value.param_uint16 = (uint16_t)value.toUInt();
547
            break;
dogmaphobic's avatar
dogmaphobic committed
548

549
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
550
            union_value.param_int16 = (int16_t)value.toInt();
551
            break;
dogmaphobic's avatar
dogmaphobic committed
552

553
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
554
            union_value.param_uint32 = (uint32_t)value.toUInt();
555
            break;
dogmaphobic's avatar
dogmaphobic committed
556

557 558 559
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
560

561 562 563
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
564

565
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
566
            union_value.param_int32 = (int32_t)value.toInt();
567 568
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
569

570
    p.param_value = union_value.param_float;
571
    p.target_system = (uint8_t)_vehicle->id();
572
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
573

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

576 577
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
578
    _vehicle->sendMessage(msg);
579 580
}

581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604
void ParameterLoader::_writeLocalParamCache()
{
    QMap<int, MapID2NamedParam> cache_map;

    foreach(int component, _mapParameterId2Name.keys()) {
        foreach(int id, _mapParameterId2Name[component].keys()) {
            const QString name(_mapParameterId2Name[component][id]);
            const Fact *fact = _mapParameterName2Variant[component][name].value<Fact*>();
            cache_map[component][id] = NamedParam(name, ParamTypeVal(fact->type(), fact->value()));
        }
    }

    QFile cache_file(QFileInfo(QSettings().fileName()).path() + QDir::separator() + "param_cache");
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

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

void ParameterLoader::_tryCacheHashLoad(int uasId, QVariant hash_value)
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
    QMap<int, MapID2NamedParam> cache_map;
605 606
    const QDir settingsDir(QFileInfo(QSettings().fileName()).dir());
    QFile cache_file(settingsDir.filePath("param_cache"));
607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634
    if (!cache_file.exists()) {
        /* no local cache, immediately refresh all params */
        refreshAllParameters();
        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 */
    foreach(int component, cache_map.keys()) {
        foreach(int id, cache_map[component].keys()) {
            const QString name(cache_map[component][id].first);
            const void *vdat = cache_map[component][id].second.second.constData();
            crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(),  crc32_value);
            crc32_value = QGC::crc32((const uint8_t *)vdat, sizeof(uint32_t), crc32_value);
        }
    }

    if (crc32_value == hash_value.toUInt()) {
        /* if the two param set hashes match, just load from the disk */
        foreach(int component, cache_map.keys()) {
            int count = cache_map[component].count();
            foreach(int id, cache_map[component].keys()) {
                const QString &name = cache_map[component][id].first;
                const QVariant &value = cache_map[component][id].second.second;
635
                const int mavType = _factTypeToMavType(static_cast<FactMetaData::ValueType_t>(cache_map[component][id].second.first));
636 637 638 639 640 641 642 643 644
                _parameterUpdate(uasId, component, name, count, id, mavType, value);
            }
        }
    } else {
        /* cache and remote hashes differ. Immediately request all params */
        refreshAllParameters();
    }
}

645 646
void ParameterLoader::_saveToEEPROM(void)
{
Don Gagne's avatar
Don Gagne committed
647 648 649 650 651 652 653 654
    if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
        _vehicle->sendMessage(msg);
        qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
    } else {
        qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
    }
655 656
}

657
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
658
{
659
    QString errors;
660
    bool userWarned = false;
dogmaphobic's avatar
dogmaphobic committed
661

662 663 664 665 666 667
    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) {
668
                if (!userWarned && (_vehicle->id() != lineMavId)) {
669 670 671
                    userWarned = true;
                    QString msg("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.");
                    QGCMessageBox::StandardButton button = QGCMessageBox::warning("Parameter Load",
672
                                                                                  msg.arg(lineMavId).arg(_vehicle->id()),
673 674 675
                                                                                  QGCMessageBox::Ok | QGCMessageBox::Cancel,
                                                                                  QGCMessageBox::Cancel);
                    if (button == QGCMessageBox::Cancel) {
676
                        return QString();
677
                    }
dogmaphobic's avatar
dogmaphobic committed
678 679
                }

680 681 682 683
                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
684

685
                if (!_autopilot->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
686 687 688 689
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
690 691
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
692

693 694
                Fact* fact = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName);
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
695 696 697 698
                    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;
                    qCDebug(ParameterLoaderLog) << error;
699 700
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
701

702
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
703 704 705 706
                fact->setValue(valStr);
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
707

708
    return errors;
709 710
}

711
void ParameterLoader::writeParametersToStream(QTextStream &stream)
712
{
713
    stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
714 715 716 717 718 719 720
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
        foreach (QString paramName, _mapParameterName2Variant[componentId].keys()) {
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
            Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
721

722
            stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->valueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
723 724
        }
    }
dogmaphobic's avatar
dogmaphobic committed
725

726 727 728 729 730 731 732 733
    stream.flush();
}

MAV_PARAM_TYPE ParameterLoader::_factTypeToMavType(FactMetaData::ValueType_t factType)
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
734

735 736
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
737

738 739
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
740

741 742
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
743

744 745
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
746

747 748
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
749

750 751 752
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
753

754 755 756 757 758 759 760 761 762 763
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

FactMetaData::ValueType_t ParameterLoader::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
764

765 766
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
767

768 769
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
770

771 772
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
773

774 775
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
776

777 778
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
779

780 781 782
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
783

784 785 786 787 788 789 790 791 792
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

void ParameterLoader::_restartWaitingParamTimer(void)
{
    _waitingParamTimeoutTimer.start();
}
793 794 795 796 797 798 799

void ParameterLoader::_checkInitialLoadComplete(void)
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
800

801 802 803 804 805 806
    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
807 808


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

812 813 814 815 816 817 818 819 820 821 822 823 824
    // Check for 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;
            qCDebug(ParameterLoaderLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
        }
    }
dogmaphobic's avatar
dogmaphobic committed
825

826
    // Check for any errors during vehicle boot
dogmaphobic's avatar
dogmaphobic committed
827

828
    UASMessageHandler* msgHandler = qgcApp()->toolbox()->uasMessageHandler();
829
    if (msgHandler->getErrorCountTotal()) {
830
        QString errors;
831
        bool firstError = true;
832
        bool errorsFound = false;
dogmaphobic's avatar
dogmaphobic committed
833

834 835 836
        msgHandler->lockAccess();
        foreach (UASMessage* msg, msgHandler->messages()) {
            if (msg->severityIsError()) {
837
                if (!firstError) {
dogmaphobic's avatar
dogmaphobic committed
838
                    errors += "<br>";
839 840
                }
                errors += " - ";
841
                errors += msg->getText();
842
                firstError = false;
843
                errorsFound = true;
844 845
            }
        }
846
        msgHandler->showErrorsInToolbar();
847
        msgHandler->unlockAccess();
dogmaphobic's avatar
dogmaphobic committed
848

849
        if (errorsFound) {
dogmaphobic's avatar
dogmaphobic committed
850
            QString errorMsg = QString("<b>Critical safety issue detected:</b><br>%1").arg(errors);
851 852
            qgcApp()->showToolBarMessage(errorMsg);
        }
853
    }
dogmaphobic's avatar
dogmaphobic committed
854

855
    // Warn of parameter load failure
dogmaphobic's avatar
dogmaphobic committed
856

857 858
    if (initialLoadFailures) {
        QGCMessageBox::critical("Parameter Load Failure",
859 860 861 862 863
                                "QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
                                "This will cause QGroundControl to be unable to display it's full user interface. "
                                "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
                                "If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
        qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
864
        emit parametersReady(true);
865 866 867 868 869
    } else {
        // No failed parameters, ok to signal ready
        _parametersReady = true;
        _determineDefaultComponentId();
        _setupGroupMap();
870
        emit parametersReady(false);
871
    }
872
}