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 "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
32
#include "FirmwarePlugin.h"
33
#include "UAS.h"
34 35 36 37

#include <QFile>
#include <QDebug>

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

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

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

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

62 63
    // 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
64

65 66 67 68
    _initialRequestTimeoutTimer.setSingleShot(true);
    _initialRequestTimeoutTimer.setInterval(6000);
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_initialRequestTimeout);

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

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

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

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

ParameterLoader::~ParameterLoader()
{

}

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

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

99 100
    _initialRequestTimeoutTimer.stop();

101 102 103 104 105 106 107 108
    qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
                                    "componentId:" << componentId <<
                                    "name:" << parameterName <<
                                    "count:" << parameterCount <<
                                    "index:" << parameterId <<
                                    "mavType:" << mavType <<
                                    "value:" << value <<
                                    ")";
dogmaphobic's avatar
dogmaphobic committed
109

110 111 112 113 114 115 116 117
#if 0
    // Handy for testing retry logic
    static int counter = 0;
    if (counter++ & 0x3) {
        qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
        return;
    }
#endif
118 119 120 121 122 123 124

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

127 128
    // Restart our waiting for param timer
    _waitingParamTimeoutTimer.start();
dogmaphobic's avatar
dogmaphobic committed
129

130 131 132 133 134
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
135 136

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

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

146 147 148
        // 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
149

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

153
    // Remove this parameter from the waiting lists
154 155 156
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
157
    qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
158 159 160 161
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

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

163 164 165
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
166

167 168 169 170 171 172 173
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

dogmaphobic's avatar
dogmaphobic committed
174

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

182 183 184 185 186 187
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
188

189 190 191 192 193 194 195 196 197 198 199 200 201 202
    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
203

204 205
    // Attempt to determine default component id
    if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) {
206
        _defaultComponentIdParam = _vehicle->firmwarePlugin()->getDefaultComponentIdParam();
207 208 209 210
    }
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        _defaultComponentId = componentId;
    }
dogmaphobic's avatar
dogmaphobic committed
211

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

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

247 248
        Fact* fact = new Fact(componentId, parameterName, factType, this);
        setMetaData = true;
dogmaphobic's avatar
dogmaphobic committed
249

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

252
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
Don Gagne's avatar
Don Gagne committed
253
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated);
254
    }
dogmaphobic's avatar
dogmaphobic committed
255

Don Gagne's avatar
Don Gagne committed
256 257
    _dataMutex.unlock();

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

260 261
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
262
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
263

264
    if (setMetaData) {
265
        _vehicle->firmwarePlugin()->addMetaDataToFact(fact, _vehicle->vehicleType());
266
    }
dogmaphobic's avatar
dogmaphobic committed
267

268 269 270
    if (waitingParamCount == 0) {
        // Now that we know vehicle is up to date persist
        _saveToEEPROM();
271
        _writeLocalParamCache();
272
    }
dogmaphobic's avatar
dogmaphobic committed
273

274
    _checkInitialLoadComplete();
275 276 277 278
}

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

285
    int componentId = fact->componentId();
286
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
287

288
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
289

290
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
291 292
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
293
    _waitingParamTimeoutTimer.start();
dogmaphobic's avatar
dogmaphobic committed
294

295
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
296

297 298
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
299 300 301 302
}

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

305 306 307 308
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

309 310
    // Reset index wait lists
    foreach (int componentId, _paramCountMap.keys()) {
311 312 313 314
        // 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;
315 316
        }
    }
dogmaphobic's avatar
dogmaphobic committed
317

318
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
319

320
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
321
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
322

323
    mavlink_message_t msg;
324 325
    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
326

327
    qCDebug(ParameterLoaderLog) << "Request to refresh all parameters";
328 329 330 331 332 333 334 335
}

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
336

337 338 339 340 341 342 343 344 345 346 347 348 349 350 351
        _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;
Don Gagne's avatar
Don Gagne committed
352
        if (componentId == FactSystem::defaultComponentId) {
Don Gagne's avatar
Don Gagne committed
353 354
            qWarning() << "Default component id not set";
        }
355
    }
dogmaphobic's avatar
dogmaphobic committed
356

357 358 359 360 361
    return componentId;
}

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

365 366 367
    _dataMutex.lock();

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

369
    if (_waitingReadParamNameMap.contains(componentId)) {
370 371
        _waitingReadParamNameMap[componentId].remove(name); // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][name] = 0;    // Add new wait entry and update retry count
372 373
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
374

375 376 377
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
378 379 380 381 382
}

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

385
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
386 387 388 389 390 391
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

392
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
393
{
394
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
395

396 397
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
398
        ret = _mapParameterName2Variant[componentId].contains(name);
399
    }
400 401

    return ret;
402 403 404 405 406
}

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

408
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) {
Don Gagne's avatar
Don Gagne committed
409 410
        qgcApp()->reportMissingParameter(componentId, name);
        return &_defaultFact;
411
    }
dogmaphobic's avatar
dogmaphobic committed
412

Don Gagne's avatar
Don Gagne committed
413
    return _mapParameterName2Variant[componentId][name].value<Fact*>();
414
}
415

Don Gagne's avatar
Don Gagne committed
416
QStringList ParameterLoader::parameterNames(int componentId)
417
{
dogmaphobic's avatar
dogmaphobic committed
418 419
    QStringList names;

420
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
421 422 423 424
        names << paramName;
    }

    return names;
425 426 427 428 429
}

void ParameterLoader::_setupGroupMap(void)
{
    foreach (int componentId, _mapParameterName2Variant.keys()) {
430
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
431 432 433 434 435 436 437 438 439 440
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
441 442 443 444 445 446

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

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

450 451
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
452 453 454 455 456 457 458 459 460 461 462 463
        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
464

465 466 467
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
468 469 470
            }
        }
    }
471 472
    // 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
473

474 475
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
476
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
477
                paramsRequested = true;
478
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
Don Gagne's avatar
Don Gagne committed
479
                _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
480
                qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
481

482 483 484 485 486 487
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
488

489 490
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
491
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
492
                paramsRequested = true;
493
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
494
                _readParameterRaw(componentId, paramName, -1);
495
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
496

497 498 499 500 501 502
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
503

504 505 506 507 508 509
Out:
    if (paramsRequested) {
        _waitingParamTimeoutTimer.start();
    }
}

510 511 512 513 514
void ParameterLoader::_tryCacheLookup()
{
    /* Start waiting for 2.5 seconds to get a cache hit and avoid loading all params over the radio */
    _cacheTimeoutTimer.start();

515
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
516 517 518 519 520 521 522
    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);
}

523 524 525 526 527 528 529 530 531
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
532
                                        _vehicle->id(),             // Target system id
533 534 535
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
536
    _vehicle->sendMessage(msg);
537 538 539 540 541 542
}

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
543

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

547 548
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
549
            union_value.param_uint8 = (uint8_t)value.toUInt();
550
            break;
dogmaphobic's avatar
dogmaphobic committed
551

552
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
553
            union_value.param_int8 = (int8_t)value.toInt();
554
            break;
dogmaphobic's avatar
dogmaphobic committed
555

556
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
557
            union_value.param_uint16 = (uint16_t)value.toUInt();
558
            break;
dogmaphobic's avatar
dogmaphobic committed
559

560
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
561
            union_value.param_int16 = (int16_t)value.toInt();
562
            break;
dogmaphobic's avatar
dogmaphobic committed
563

564
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
565
            union_value.param_uint32 = (uint32_t)value.toUInt();
566
            break;
dogmaphobic's avatar
dogmaphobic committed
567

568 569 570
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
571

572 573 574
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
575

576
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
577
            union_value.param_int32 = (int32_t)value.toInt();
578 579
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
580

581
    p.param_value = union_value.param_float;
582
    p.target_system = (uint8_t)_vehicle->id();
583
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
584

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

587 588
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
589
    _vehicle->sendMessage(msg);
590 591
}

592 593 594 595 596 597 598 599
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*>();
Don Gagne's avatar
Don Gagne committed
600
            cache_map[component][id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue()));
601 602 603 604 605 606 607 608 609 610 611 612 613 614 615
        }
    }

    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;
616 617
    const QDir settingsDir(QFileInfo(QSettings().fileName()).dir());
    QFile cache_file(settingsDir.filePath("param_cache"));
618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645
    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;
646
                const int mavType = _factTypeToMavType(static_cast<FactMetaData::ValueType_t>(cache_map[component][id].second.first));
647 648 649 650 651 652 653 654 655
                _parameterUpdate(uasId, component, name, count, id, mavType, value);
            }
        }
    } else {
        /* cache and remote hashes differ. Immediately request all params */
        refreshAllParameters();
    }
}

656 657
void ParameterLoader::_saveToEEPROM(void)
{
Don Gagne's avatar
Don Gagne committed
658 659 660 661 662 663 664 665
    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";
    }
666 667
}

668
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
669
{
670
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
671

672 673 674 675 676 677
    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
678 679
                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
680 681
                }

682 683 684 685
                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
686

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

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

704
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
705
                fact->setRawValue(valStr);
706 707 708
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
709

710
    return errors;
711 712
}

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

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

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

728 729 730 731 732 733 734 735
    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
736

737 738
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
739

740 741
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
742

743 744
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
745

746 747
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
748

749 750
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
751

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

756 757 758 759 760 761 762 763 764 765
        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
766

767 768
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
769

770 771
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
772

773 774
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
775

776 777
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
778

779 780
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
781

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

786 787 788 789 790 791 792 793 794
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

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

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

803 804 805 806 807 808
    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
809 810


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

814 815 816 817 818 819 820 821 822 823 824 825 826
    // 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
827

828
    // Check for any errors during vehicle boot
dogmaphobic's avatar
dogmaphobic committed
829

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

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

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

857
    // Warn of parameter load failure
dogmaphobic's avatar
dogmaphobic committed
858

859
    if (initialLoadFailures) {
860 861 862 863
        qgcApp()->showMessage("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.");
864
        qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
865
        emit parametersReady(true);
866 867 868 869 870
    } else {
        // No failed parameters, ok to signal ready
        _parametersReady = true;
        _determineDefaultComponentId();
        _setupGroupMap();
871
        emit parametersReady(false);
872
    }
873
}
874 875 876 877 878 879 880

void ParameterLoader::_initialRequestTimeout(void)
{
    qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying");
    refreshAllParameters();
    _initialRequestTimeoutTimer.start();
}