UASParameterCommsMgr.cc 17.6 KB
Newer Older
1 2
#include "UASParameterCommsMgr.h"

tstellanova's avatar
tstellanova committed
3 4
#include <QSettings>

5
#include "QGCUASParamManagerInterface.h"
6 7
#include "UASInterface.h"

8 9


10 11
#define RC_CAL_CHAN_MAX 8

12
UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent) :
tstellanova's avatar
tstellanova committed
13
    QObject(parent),
tstellanova's avatar
tstellanova committed
14
    lastReceiveTime(0),
15
    mav(NULL),
16
    maxSilenceTimeout(30000),
17
    paramDataModel(NULL),
18 19 20
    retransmitBurstLimit(5),
    silenceTimeout(1000),
    transmissionListMode(false)
21
{
22 23 24
    // We signal to ourselves to start/stop timer on our own thread
    connect(this, SIGNAL(_startSilenceTimer(void)), this, SLOT(_startSilenceTimerOnThisThread(void)));
    connect(this, SIGNAL(_stopSilenceTimer(void)), this, SLOT(_stopSilenceTimerOnThisThread(void)));
25 26 27 28 29
}

UASParameterCommsMgr* UASParameterCommsMgr::initWithUAS(UASInterface* uas)
{
    mav = uas;
30
    paramDataModel = mav->getParamManager()->dataModel();
tstellanova's avatar
tstellanova committed
31 32 33 34 35
    loadParamCommsSettings();

    //Requesting parameters one-by-one from mav
    connect(this, SIGNAL(parameterUpdateRequestedById(int,int)),
            mav, SLOT(requestParameter(int,int)));
36 37

    // Sending params to the UAS
38
    connect(this, SIGNAL(commitPendingParameter(int,QString,QVariant)),
39
            mav, SLOT(setParameter(int,QString,QVariant)));
40

41
    // Received parameter updates from UAS
42 43
    connect(mav, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)),
            this, SLOT(receivedParameterUpdate(int,int,int,int,QString,QVariant)));
44

45 46
    connect(&silenceTimer, SIGNAL(timeout()),
            this,SLOT(silenceTimerExpired()));
tstellanova's avatar
tstellanova committed
47

48
    return this;
49 50 51
}


tstellanova's avatar
tstellanova committed
52

53

tstellanova's avatar
tstellanova committed
54 55 56
void UASParameterCommsMgr::loadParamCommsSettings()
{
    QSettings settings;
57
    //TODO these are duplicates of MAVLinkProtocol settings...seems wrong to use them in two places
tstellanova's avatar
tstellanova committed
58
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
tstellanova's avatar
tstellanova committed
59
    bool ok;
60
    int val = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", 1000).toInt(&ok);
tstellanova's avatar
tstellanova committed
61
    if (ok) {
62 63
        silenceTimeout = val;
        qDebug() << "silenceTimeout" << silenceTimeout;
tstellanova's avatar
tstellanova committed
64
    }
65

tstellanova's avatar
tstellanova committed
66 67 68
    settings.endGroup();
}

69 70


71 72 73 74 75 76 77 78 79 80
/**
 * Send a request to deliver the list of onboard parameters
 * from the MAV.
 */
void UASParameterCommsMgr::requestParameterList()
{
    if (!mav) {
        return;
    }

81
    if (!transmissionListMode) {
82 83 84
        transmissionListMode = true;//TODO eliminate?
        //we use (compId 0, paramId 0) as  indicating all params for the system
        markReadParamWaiting(0,0);
85
        mav->requestParameters();
86
        updateSilenceTimer();
87 88 89
    }
    else {
        qDebug() << __FILE__ << __LINE__ << "Ignoring requestParameterList because we're receiving params list";
90 91 92 93 94
    }

}


95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114
void UASParameterCommsMgr::markReadParamWaiting(int compId, int paramId)
{
    if (!readsWaiting.contains(compId)) {
        readsWaiting.insert(compId, new QSet<int>());
    }

    readsWaiting.value(compId)->insert(paramId);
}

void UASParameterCommsMgr::markWriteParamWaiting(int compId, QString paramName, QVariant value)
{
    //ensure we have a map for this compId
    if (!writesWaiting.contains(compId)) {
        writesWaiting.insert(compId, new QMap<QString, QVariant>());
    }

    // Insert it in missing write ACK list
    writesWaiting.value(compId)->insert(paramName, value);
}

115 116 117 118
/*
 Empty read retransmission list
 Empty write retransmission list
*/
tstellanova's avatar
tstellanova committed
119
void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount )
120 121 122
{
    qDebug() << __FILE__ << __LINE__ << "clearRetransmissionLists";

tstellanova's avatar
tstellanova committed
123
    missingReadCount = 0;
124 125 126 127
    QList<int> compIds = readsWaiting.keys();
    foreach (int compId, compIds) {
        missingReadCount += readsWaiting.value(compId)->count();
        readsWaiting.value(compId)->clear();
128 129
    }

tstellanova's avatar
tstellanova committed
130
    missingWriteCount = 0;
131 132 133 134
    compIds = writesWaiting.keys();
    foreach (int compId, compIds) {
        missingWriteCount += writesWaiting.value(compId)->count();
        writesWaiting.value(compId)->clear();
135 136 137 138 139
    }

}


140
void UASParameterCommsMgr::emitPendingParameterCommit(int compId, const QString& key, QVariant& value)
141 142 143 144 145 146 147
{
    int paramType = (int)value.type();
    switch (paramType)
    {
    case QVariant::Char:
    {
        QVariant fixedValue(QChar((unsigned char)value.toInt()));
148
        emit commitPendingParameter(compId, key, fixedValue);
149 150 151 152 153
    }
        break;
    case QVariant::Int:
    {
        QVariant fixedValue(value.toInt());
154
        emit commitPendingParameter(compId, key, fixedValue);
155 156 157 158 159
    }
        break;
    case QVariant::UInt:
    {
        QVariant fixedValue(value.toUInt());
160
        emit commitPendingParameter(compId, key, fixedValue);
161 162 163 164 165
    }
        break;
    case QMetaType::Float:
    {
        QVariant fixedValue(value.toFloat());
166
        emit commitPendingParameter(compId, key, fixedValue);
167 168 169
    }
        break;
    default:
170
        qCritical() << "ABORTED PARAM SEND, INVALID QVARIANT TYPE" << paramType;
171 172 173
        return;
    }

174
    setParameterStatusMsg(tr("Writing %1: %2 for comp. %3").arg(key).arg(value.toDouble()).arg(compId));
175 176 177 178 179 180 181 182 183

}


void UASParameterCommsMgr::resendReadWriteRequests()
{
    int compId;
    QList<int> compIds;

184
    // Re-request at maximum retransmitBurstLimit parameters at once
185 186
    // to prevent link flooding'
    int requestedReadCount = 0;
187
    compIds = readsWaiting.keys();
188 189
    foreach (compId, compIds) {
        // Request n parameters from this component (at maximum)
190 191
        QSet<int>* missingReadParams = readsWaiting.value(compId, NULL);
        qDebug() << "compId " << compId << "readsWaiting:" << missingReadParams->count();
192
        foreach (int paramId, *missingReadParams) {
193 194 195 196 197 198
            if (0 == paramId && 0 == compId) {
                mav->requestParameters();
                //don't request any other params individually for this component
                break;
            }
            if (requestedReadCount < retransmitBurstLimit) {
199
                //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << paramId << "FROM COMPONENT #" << compId;
200 201 202 203 204 205 206 207 208 209 210
                emit parameterUpdateRequestedById(compId, paramId);
                setParameterStatusMsg(tr("Requested retransmission of #%1").arg(paramId+1));
                requestedReadCount++;
            }
            else {
                qDebug() << "Throttling read retransmit requests at" << requestedReadCount;
                break;
            }
        }
    }

211
    // Re-request at maximum retransmitBurstLimit parameters at once
212 213
    // to prevent write-request link flooding
    int requestedWriteCount = 0;
214
    compIds = writesWaiting.keys();
215
    foreach (compId, compIds) {
216 217 218
        QMap <QString, QVariant>* missingWriteParams = writesWaiting.value(compId);
        foreach (QString key, missingWriteParams->keys()) {
            if (requestedWriteCount < retransmitBurstLimit) {
219
                // Re-request write operation
220
                QVariant value = missingWriteParams->value(key);
221
                emitPendingParameterCommit(compId, key, value);
222 223 224 225 226 227 228 229 230
                requestedWriteCount++;
            }
            else {
                qDebug() << "Throttling write retransmit requests at" << requestedWriteCount;
                break;
            }
        }
    }

231 232
    updateSilenceTimer();

233 234
}

235 236 237
void UASParameterCommsMgr::resetAfterListReceive()
{
    transmissionListMode = false;
238
    knownParamListSize.clear();
239 240
}

241
void UASParameterCommsMgr::silenceTimerExpired()
242
{
243
    quint64 curTime = QGC::groundTimeMilliseconds();
244 245
    int elapsed = (int)(curTime - lastSilenceTimerReset);
    qDebug() << "silenceTimerExpired elapsed:" << elapsed;
246

247
    if (elapsed < silenceTimeout) {
248
        //reset the guard timer: it fired prematurely
249
        updateSilenceTimer();
250 251
        return;
    }
252

253 254
    int totalElapsed = (int)(curTime - lastReceiveTime);
    if (totalElapsed > maxSilenceTimeout) {
255
        qDebug() << "maxSilenceTimeout exceeded: " << totalElapsed;
256 257
        int missingReads, missingWrites;
        clearRetransmissionLists(missingReads,missingWrites);
258
        emit _stopSilenceTimer(); // Stop timer on our thread;
tstellanova's avatar
tstellanova committed
259
        lastReceiveTime = 0;
260
        lastSilenceTimerReset = curTime;
261
        setParameterStatusMsg(tr("TIMEOUT: Abandoning %1 reads %2 writes after %3 seconds").arg(missingReads).arg(missingWrites).arg(totalElapsed/1000));
262 263
    }
    else {
264
        resendReadWriteRequests();
265 266 267 268
    }
}


269
void UASParameterCommsMgr::requestParameterUpdate(int compId, const QString& paramName)
270 271
{
    if (mav) {
272 273 274
        mav->requestParameter(compId, paramName);
        //TODO track these read requests with a paramName but no param ID  : use index in getOnboardParamsForComponent?
        //ensure we keep track of every single read request
275 276 277
    }
}

278 279 280 281 282 283 284 285 286 287 288
void UASParameterCommsMgr::requestRcCalibrationParamsUpdate()
{
    if (!transmissionListMode) {
        QString minTpl("RC%1_MIN");
        QString maxTpl("RC%1_MAX");
        QString trimTpl("RC%1_TRIM");
        QString revTpl("RC%1_REV");

        // Do not request the RC type, as these values depend on this
        // active onboard parameter

289 290

        int defCompId = paramDataModel->getDefaultComponentId();
291 292
        for (unsigned int i = 1; i < (RC_CAL_CHAN_MAX+1); ++i)  {
            qDebug() << "Request RC " << i;
293 294 295 296
            requestParameterUpdate(defCompId, minTpl.arg(i));
            requestParameterUpdate(defCompId, trimTpl.arg(i));
            requestParameterUpdate(defCompId, maxTpl.arg(i));
            requestParameterUpdate(defCompId, revTpl.arg(i));
297 298 299 300 301 302 303 304 305
            QGC::SLEEP::usleep(5000);
        }
    }
    else {
        qDebug() << __FILE__ << __LINE__ << "Ignoring requestRcCalibrationParamsUpdate because we're receiving params list";
    }
}


306 307 308 309 310
/**
 * @param component the subsystem which has the parameter
 * @param parameterName name of the parameter, as delivered by the system
 * @param value value of the parameter
 */
311
void UASParameterCommsMgr::setParameter(int compId, QString paramName, QVariant value, bool forceSend)
312
{
313
    if (paramName.isEmpty()) {
314 315 316 317 318
        return;
    }

    double dblValue = value.toDouble();

319 320
    if (paramDataModel->isValueLessThanParamMin(paramName,dblValue)) {
        setParameterStatusMsg(tr("REJ. %1, %2 < min").arg(paramName).arg(dblValue),
tstellanova's avatar
tstellanova committed
321 322
                              ParamCommsStatusLevel_Error
                              );
323 324
        return;
    }
325 326
    if (paramDataModel->isValueGreaterThanParamMax(paramName,dblValue)) {
        setParameterStatusMsg(tr("REJ. %1, %2 > max").arg(paramName).arg(dblValue),
tstellanova's avatar
tstellanova committed
327 328
                              ParamCommsStatusLevel_Error
                              );
329 330
        return;
    }
331

332 333 334 335 336 337 338 339 340 341
	if (!forceSend) {
		QVariant onboardVal;
		paramDataModel->getOnboardParamValue(compId,paramName,onboardVal);
		if (onboardVal == value) {
			setParameterStatusMsg(tr("REJ. %1 already %2").arg(paramName).arg(dblValue),
				ParamCommsStatusLevel_Warning
				);
			return;
		}
	}
342

343 344 345
    emitPendingParameterCommit(compId, paramName, value);

    //Add this request to list of writes not yet ack'd
346

347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365
    markWriteParamWaiting( compId,  paramName,  value);
    updateSilenceTimer();


}

void UASParameterCommsMgr::updateSilenceTimer()
{
    //if there are pending reads or writes, ensure we timeout in a little while
    //if we hear nothing but silence from our partner

    int missReadCount = 0;
    foreach (int key, readsWaiting.keys()) {
        missReadCount +=  readsWaiting.value(key)->count();
    }

    int missWriteCount = 0;
    foreach (int key, writesWaiting.keys()) {
        missWriteCount += writesWaiting.value(key)->count();
366 367 368
    }


369 370
    if (missReadCount > 0 || missWriteCount > 0) {
        lastSilenceTimerReset = QGC::groundTimeMilliseconds();
tstellanova's avatar
tstellanova committed
371 372 373
        if (0 == lastReceiveTime) {
            lastReceiveTime = lastSilenceTimerReset;
        }
374 375
        // We signal this to ourselves so timer is started on the right thread
        emit _startSilenceTimer();
376
    }
377
    else {
378 379 380
        //all parameters have been received, broadcast to UI
        emit parameterListUpToDate();
        resetAfterListReceive();
381
        emit _stopSilenceTimer(); // Stop timer on our thread;
tstellanova's avatar
tstellanova committed
382
        lastReceiveTime = 0;
383 384
    }

385 386


387 388
}

389

tstellanova's avatar
tstellanova committed
390
void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level)
391
{
Lorenz Meier's avatar
Lorenz Meier committed
392
    //qDebug() << "parameterStatusMsg: " << msg;
tstellanova's avatar
tstellanova committed
393
    emit parameterStatusMsgUpdated(msg,level);
394
}
tstellanova's avatar
tstellanova committed
395 396 397

void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value)
{
398
    Q_UNUSED(uas); //this object is assigned to one UAS only
399
    lastReceiveTime = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
400
    // qDebug() << "compId" << compId << "receivedParameterUpdate:" << paramName;
401

402
    //notify the data model that we have an updated param
403
    paramDataModel->handleParamUpdate(compId,paramName,value);
tstellanova's avatar
tstellanova committed
404 405


406 407 408 409 410 411 412
    // Ensure we have missing read/write lists for this compId
    if (!readsWaiting.contains(compId)) {
        readsWaiting.insert(compId, new QSet<int>());
    }
    if (!writesWaiting.contains(compId) ) {
        writesWaiting.insert(compId,new QMap<QString,QVariant>());
    }
413

414
    QSet<int>* compMissingReads =  readsWaiting.value(compId);
tstellanova's avatar
tstellanova committed
415 416
    // List mode is different from single parameter transfers
    if (transmissionListMode) {
417 418
        // Only accept the list size once on the first packet from each component
        if (!knownParamListSize.contains(compId)) {
tstellanova's avatar
tstellanova committed
419
            // Mark list size as known
420
            knownParamListSize.insert(compId,paramCount);
tstellanova's avatar
tstellanova committed
421

422 423
            //remove our placeholder read request for all params
            readsWaiting.value(0)->remove(0);
tstellanova's avatar
tstellanova committed
424

425 426 427
            qDebug() << "Mark all parameters as missing: " << paramCount;
            for (int i = 1; i < paramCount; ++i) { //param Id 0 is  "all parameters" and not valid
                compMissingReads->insert(i);
tstellanova's avatar
tstellanova committed
428 429 430 431
            }
        }
    }

432

tstellanova's avatar
tstellanova committed
433
    // Mark this parameter as received in read list
434 435
    compMissingReads->remove(paramId);

tstellanova's avatar
tstellanova committed
436 437 438

    bool justWritten = false;
    bool writeMismatch = false;
439

tstellanova's avatar
tstellanova committed
440
    // Mark this parameter as received in write ACK list
441 442
    QMap<QString, QVariant>* compMissingWrites = writesWaiting.value(compId);
    if (!compMissingWrites) {
443
        //we sometimes send a write request on compId 0 and get a response on a nonzero compId eg 50
444
        compMissingWrites = writesWaiting.value(0);
445
    }
446
    if (compMissingWrites && compMissingWrites->contains(paramName)) {
tstellanova's avatar
tstellanova committed
447
        justWritten = true;
448
        if (compMissingWrites->value(paramName) != value) {
tstellanova's avatar
tstellanova committed
449 450
            writeMismatch = true;
        }
451
        compMissingWrites->remove(paramName);
tstellanova's avatar
tstellanova committed
452 453 454
    }


455
    if (justWritten) {
456
        int waitingWritesCount = compMissingWrites->count();
457
        if (!writeMismatch) {
458 459 460 461 462 463
            setParameterStatusMsg(tr("SUCCESS: Wrote %2 (#%1): %3").arg(paramId+1).arg(paramName).arg(value.toDouble()));
        }

        if (!writeMismatch) {
            if (0 == waitingWritesCount) {
                setParameterStatusMsg(tr("SUCCESS: Wrote all params for component %1").arg(compId));
464 465 466 467
                if (persistParamsAfterSend) {
                    writeParamsToPersistentStorage();
                    persistParamsAfterSend = false;
                }
468 469 470 471
            }
        }
        else  {
            // Mismatch, tell user
472
            setParameterStatusMsg(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(paramName).arg(compMissingWrites->value(paramName).toDouble()).arg(value.toDouble()),
473 474
                                  ParamCommsStatusLevel_Warning);
        }
tstellanova's avatar
tstellanova committed
475 476
    }
    else {
477 478 479
        int waitingReadsCount = compMissingReads->count();

        if (0 == waitingReadsCount) {
tstellanova's avatar
tstellanova committed
480 481 482 483 484 485
            // Transmission done
            QTime time = QTime::currentTime();
            QString timeString = time.toString();
            setParameterStatusMsg(tr("All received. (updated at %1)").arg(timeString));
        }
        else {
486
            // Waiting to receive more
487
            QString val = QString("%1").arg(value.toFloat(), 5, 'f', 1, QChar(' '));
488 489
            setParameterStatusMsg(tr("OK: %1 %2 (%3/%4)").arg(paramName).arg(val).arg(paramCount-waitingReadsCount).arg(paramCount),
                                  ParamCommsStatusLevel_OK);
tstellanova's avatar
tstellanova committed
490 491 492
        }
    }

493 494 495
    updateSilenceTimer();


tstellanova's avatar
tstellanova committed
496 497 498 499 500 501 502
}


void UASParameterCommsMgr::writeParamsToPersistentStorage()
{
    if (mav) {
        mav->writeParametersToStorage(); //TODO track timeout, retransmit etc?
503
        persistParamsAfterSend = false; //done
tstellanova's avatar
tstellanova committed
504 505 506 507
    }
}


508
void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent, bool forceSend)
tstellanova's avatar
tstellanova committed
509
{
510 511
    persistParamsAfterSend |= copyToPersistent;

tstellanova's avatar
tstellanova committed
512 513
    // Iterate through all components, through all pending parameters and send them to UAS
    int parametersSent = 0;
514
    QMap<int, QMap<QString, QVariant>*>* changedValues = paramDataModel->getAllPendingParams();
tstellanova's avatar
tstellanova committed
515
    QMap<int, QMap<QString, QVariant>*>::iterator i;
516
    for (i = changedValues->begin(); i != changedValues->end(); ++i) {
tstellanova's avatar
tstellanova committed
517
        // Iterate through the parameters of the component
tstellanova's avatar
tstellanova committed
518 519 520 521 522 523
        int compId = i.key();
        QMap<QString, QVariant>* paramList = i.value();
        QMap<QString, QVariant>::iterator j;
        setParameterStatusMsg(tr("%1 pending params for component %2").arg(paramList->count()).arg(compId));

        for (j = paramList->begin(); j != paramList->end(); ++j) {
524
            setParameter(compId, j.key(), j.value(), forceSend);
tstellanova's avatar
tstellanova committed
525
            parametersSent++;
tstellanova's avatar
tstellanova committed
526 527 528 529
        }
    }

    // Change transmission status if necessary
530
    if (0 == parametersSent) {
tstellanova's avatar
tstellanova committed
531
        setParameterStatusMsg(tr("No transmission: No changed values."),ParamCommsStatusLevel_Warning);
532 533
    }
    else {
tstellanova's avatar
tstellanova committed
534
        setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent));
535
        qDebug() << "Pending parameters now:" << paramDataModel->countPendingParams();
tstellanova's avatar
tstellanova committed
536
    }
537 538 539


    updateSilenceTimer();
tstellanova's avatar
tstellanova committed
540 541
}

542 543
UASParameterCommsMgr::~UASParameterCommsMgr()
{
544
    silenceTimer.stop();
545 546 547 548 549

    QString ptrStr;
    ptrStr.sprintf("%8p", this);
    qDebug() <<  "UASParameterCommsMgr destructor: " << ptrStr ;

550 551
}

552 553 554 555 556 557 558 559 560
void UASParameterCommsMgr::_startSilenceTimerOnThisThread(void)
{
    silenceTimer.start(silenceTimeout);
}

void UASParameterCommsMgr::_stopSilenceTimerOnThisThread(void)
{
    silenceTimer.stop();
}