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

tstellanova's avatar
tstellanova committed
3
#include <QSettings>
Don Gagne's avatar
Don Gagne committed
4
#include <QDebug>
tstellanova's avatar
tstellanova committed
5

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

9 10


11 12
#define RC_CAL_CHAN_MAX 8

13
UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent) :
tstellanova's avatar
tstellanova committed
14
    QObject(parent),
tstellanova's avatar
tstellanova committed
15
    lastReceiveTime(0),
16
    mav(NULL),
17
    maxSilenceTimeout(30000),
18
    paramDataModel(NULL),
19 20 21
    retransmitBurstLimit(5),
    silenceTimeout(1000),
    transmissionListMode(false)
22
{
23 24 25
    // 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)));
26 27 28 29 30
}

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

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

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

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

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

49
    return this;
50 51 52
}


tstellanova's avatar
tstellanova committed
53

54

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

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

70 71


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

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

}


96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115
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);
}

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

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

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

}


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

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

}


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

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

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

232 233
    updateSilenceTimer();

234 235
}

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

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

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

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


270
void UASParameterCommsMgr::requestParameterUpdate(int compId, const QString& paramName)
271 272
{
    if (mav) {
273 274 275
        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
276 277 278
    }
}

279 280 281 282 283 284 285 286 287 288 289
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

290 291

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


307 308 309 310 311
/**
 * @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
 */
312
void UASParameterCommsMgr::setParameter(int compId, QString paramName, QVariant value, bool forceSend)
313
{
314
    if (paramName.isEmpty()) {
315 316 317 318 319
        return;
    }

    double dblValue = value.toDouble();

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

333 334 335 336 337 338 339 340 341 342
	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;
		}
	}
343

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

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

348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366
    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();
367 368 369
    }


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

386 387


388 389
}

390

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

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

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


407 408 409 410 411 412 413
    // 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>());
    }
414

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

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

426 427 428
            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
429 430 431 432
            }
        }
    }

433

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

tstellanova's avatar
tstellanova committed
437 438 439

    bool justWritten = false;
    bool writeMismatch = false;
440

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


456
    if (justWritten) {
457
        int waitingWritesCount = compMissingWrites->count();
458
        if (!writeMismatch) {
459 460 461 462 463 464
            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));
465 466 467 468
                if (persistParamsAfterSend) {
                    writeParamsToPersistentStorage();
                    persistParamsAfterSend = false;
                }
469 470 471 472
            }
        }
        else  {
            // Mismatch, tell user
473
            setParameterStatusMsg(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(paramName).arg(compMissingWrites->value(paramName).toDouble()).arg(value.toDouble()),
474 475
                                  ParamCommsStatusLevel_Warning);
        }
tstellanova's avatar
tstellanova committed
476 477
    }
    else {
478 479 480
        int waitingReadsCount = compMissingReads->count();

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

494 495 496
    updateSilenceTimer();


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


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


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

tstellanova's avatar
tstellanova committed
513 514
    // Iterate through all components, through all pending parameters and send them to UAS
    int parametersSent = 0;
515
    QMap<int, QMap<QString, QVariant>*>* changedValues = paramDataModel->getAllPendingParams();
tstellanova's avatar
tstellanova committed
516
    QMap<int, QMap<QString, QVariant>*>::iterator i;
517
    for (i = changedValues->begin(); i != changedValues->end(); ++i) {
tstellanova's avatar
tstellanova committed
518
        // Iterate through the parameters of the component
tstellanova's avatar
tstellanova committed
519 520 521 522 523 524
        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) {
525
            setParameter(compId, j.key(), j.value(), forceSend);
tstellanova's avatar
tstellanova committed
526
            parametersSent++;
tstellanova's avatar
tstellanova committed
527 528 529 530
        }
    }

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


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

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

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

551 552
}

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

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