UASParameterCommsMgr.cc 18.9 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
#include "UASInterface.h"
8 9
#include "MAVLinkProtocol.h"
#include "MainWindow.h"
10
#include "QGCLoggingCategory.h"
11

12 13
#define RC_CAL_CHAN_MAX 8

14
QGC_LOGGING_CATEGORY(UASParameterCommsMgrLog, "UASParameterCommsMgrLog")
15

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

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

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

    // Sending params to the UAS
42
    connect(this, SIGNAL(commitPendingParameter(int,QString,QVariant)),
43
            mav, SLOT(setParameter(int,QString,QVariant)));
44

45
    // Received parameter updates from UAS
46 47
    connect(mav, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)),
            this, SLOT(receivedParameterUpdate(int,int,int,int,QString,QVariant)));
48

49 50
    connect(&silenceTimer, SIGNAL(timeout()),
            this,SLOT(silenceTimerExpired()));
tstellanova's avatar
tstellanova committed
51

52
    return this;
53 54 55
}


tstellanova's avatar
tstellanova committed
56

57

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

tstellanova's avatar
tstellanova committed
70 71 72
    settings.endGroup();
}

73 74
void UASParameterCommsMgr::_sendParamRequestListMsg(void)
{
75
    MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
76 77 78 79 80 81
    Q_ASSERT(mavlink);
    
    mavlink_message_t msg;
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, mav->getUASID(), MAV_COMP_ID_ALL);
    mav->sendMessage(msg);
}
82

83 84 85 86 87 88 89 90 91
/**
 * Send a request to deliver the list of onboard parameters
 * from the MAV.
 */
void UASParameterCommsMgr::requestParameterList()
{
    if (!mav) {
        return;
    }
92
    
93

94
    if (!transmissionListMode) {
95
        qCDebug(UASParameterCommsMgrLog) << "Requesting full parameter list";
96 97 98
        transmissionListMode = true;//TODO eliminate?
        //we use (compId 0, paramId 0) as  indicating all params for the system
        markReadParamWaiting(0,0);
99 100 101
        
        _sendParamRequestListMsg();
        
102
        updateSilenceTimer();
103 104
    }
    else {
105
        qCDebug(UASParameterCommsMgrLog) << "Ignoring requestParameterList because we're receiving params list";
106 107 108 109 110
    }

}


111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
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);
}

131 132 133 134
/*
 Empty read retransmission list
 Empty write retransmission list
*/
tstellanova's avatar
tstellanova committed
135
void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount )
136
{
137
    qCDebug(UASParameterCommsMgrLog) << "Clearing re-transmission lists";
138

tstellanova's avatar
tstellanova committed
139
    missingReadCount = 0;
140 141 142 143
    QList<int> compIds = readsWaiting.keys();
    foreach (int compId, compIds) {
        missingReadCount += readsWaiting.value(compId)->count();
        readsWaiting.value(compId)->clear();
144 145
    }

tstellanova's avatar
tstellanova committed
146
    missingWriteCount = 0;
147 148 149 150
    compIds = writesWaiting.keys();
    foreach (int compId, compIds) {
        missingWriteCount += writesWaiting.value(compId)->count();
        writesWaiting.value(compId)->clear();
151 152 153 154 155
    }

}


156
void UASParameterCommsMgr::emitPendingParameterCommit(int compId, const QString& key, QVariant& value)
157 158 159 160 161 162 163
{
    int paramType = (int)value.type();
    switch (paramType)
    {
    case QVariant::Char:
    {
        QVariant fixedValue(QChar((unsigned char)value.toInt()));
164
        emit commitPendingParameter(compId, key, fixedValue);
165 166 167 168 169
    }
        break;
    case QVariant::Int:
    {
        QVariant fixedValue(value.toInt());
170
        emit commitPendingParameter(compId, key, fixedValue);
171 172 173 174 175
    }
        break;
    case QVariant::UInt:
    {
        QVariant fixedValue(value.toUInt());
176
        emit commitPendingParameter(compId, key, fixedValue);
177 178 179 180 181
    }
        break;
    case QMetaType::Float:
    {
        QVariant fixedValue(value.toFloat());
182
        emit commitPendingParameter(compId, key, fixedValue);
183 184 185
    }
        break;
    default:
186
        qCritical() << "ABORTED PARAM SEND, INVALID QVARIANT TYPE" << paramType;
187 188 189
        return;
    }

190
    setParameterStatusMsg(tr("Writing %1: %2 for comp. %3").arg(key).arg(value.toDouble()).arg(compId));
191 192 193 194 195 196 197 198 199

}


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

200
    // Re-request at maximum retransmitBurstLimit parameters at once
201 202
    // to prevent link flooding'
    int requestedReadCount = 0;
203
    compIds = readsWaiting.keys();
204 205
    foreach (compId, compIds) {
        // Request n parameters from this component (at maximum)
206 207
        QSet<int>* missingReadParams = readsWaiting.value(compId, NULL);
        qDebug() << "compId " << compId << "readsWaiting:" << missingReadParams->count();
208
        foreach (int paramId, *missingReadParams) {
209
            if (0 == paramId && 0 == compId) {
210
                _sendParamRequestListMsg();
211 212 213 214
                //don't request any other params individually for this component
                break;
            }
            if (requestedReadCount < retransmitBurstLimit) {
215
                //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << paramId << "FROM COMPONENT #" << compId;
216 217 218 219 220
                emit parameterUpdateRequestedById(compId, paramId);
                setParameterStatusMsg(tr("Requested retransmission of #%1").arg(paramId+1));
                requestedReadCount++;
            }
            else {
221
                qCDebug(UASParameterCommsMgrLog) << "Throttling read retransmit requests at" << requestedReadCount;
222 223 224 225 226
                break;
            }
        }
    }

227
    // Re-request at maximum retransmitBurstLimit parameters at once
228 229
    // to prevent write-request link flooding
    int requestedWriteCount = 0;
230
    compIds = writesWaiting.keys();
231
    foreach (compId, compIds) {
232 233 234
        QMap <QString, QVariant>* missingWriteParams = writesWaiting.value(compId);
        foreach (QString key, missingWriteParams->keys()) {
            if (requestedWriteCount < retransmitBurstLimit) {
235
                // Re-request write operation
236
                QVariant value = missingWriteParams->value(key);
237
                emitPendingParameterCommit(compId, key, value);
238 239 240
                requestedWriteCount++;
            }
            else {
241
                qCDebug(UASParameterCommsMgrLog) << "Throttling write retransmit requests at" << requestedWriteCount;
242 243 244 245 246
                break;
            }
        }
    }

247 248
    updateSilenceTimer();

249 250
}

251 252 253
void UASParameterCommsMgr::resetAfterListReceive()
{
    transmissionListMode = false;
254
    knownParamListSize.clear();
255 256
}

257
void UASParameterCommsMgr::silenceTimerExpired()
258
{
259
    quint64 curTime = QGC::groundTimeMilliseconds();
260
    int elapsed = (int)(curTime - lastSilenceTimerReset);
261
    qCDebug(UASParameterCommsMgrLog) << "silenceTimerExpired elapsed:" << elapsed;
262

263
    if (elapsed < silenceTimeout) {
264
        //reset the guard timer: it fired prematurely
265
        updateSilenceTimer();
266 267
        return;
    }
268

269 270
    int totalElapsed = (int)(curTime - lastReceiveTime);
    if (totalElapsed > maxSilenceTimeout) {
271
        qCDebug(UASParameterCommsMgrLog) << "maxSilenceTimeout exceeded: " << totalElapsed;
272 273
        int missingReads, missingWrites;
        clearRetransmissionLists(missingReads,missingWrites);
274
        emit _stopSilenceTimer(); // Stop timer on our thread;
tstellanova's avatar
tstellanova committed
275
        lastReceiveTime = 0;
276
        lastSilenceTimerReset = curTime;
277
        setParameterStatusMsg(tr("TIMEOUT: Abandoning %1 reads %2 writes after %3 seconds").arg(missingReads).arg(missingWrites).arg(totalElapsed/1000));
278 279
    }
    else {
280
        resendReadWriteRequests();
281 282 283 284
    }
}


285
void UASParameterCommsMgr::requestParameterUpdate(int compId, const QString& paramName)
286 287
{
    if (mav) {
288
        mav->requestParameter(compId, paramName);
Don Gagne's avatar
Don Gagne committed
289
        qCDebug(UASParameterCommsMgrLog) << "Requested update for" << compId << paramName;
290 291
        //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
292 293 294
    }
}

295 296 297 298 299 300 301 302 303 304 305
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

306 307

        int defCompId = paramDataModel->getDefaultComponentId();
308 309
        for (unsigned int i = 1; i < (RC_CAL_CHAN_MAX+1); ++i)  {
            qDebug() << "Request RC " << i;
310 311 312 313
            requestParameterUpdate(defCompId, minTpl.arg(i));
            requestParameterUpdate(defCompId, trimTpl.arg(i));
            requestParameterUpdate(defCompId, maxTpl.arg(i));
            requestParameterUpdate(defCompId, revTpl.arg(i));
314 315 316 317
            QGC::SLEEP::usleep(5000);
        }
    }
    else {
318
        qCDebug(UASParameterCommsMgrLog) << "Ignoring requestRcCalibrationParamsUpdate because we're receiving params list";
319 320 321 322
    }
}


323 324 325 326 327
/**
 * @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
 */
328
void UASParameterCommsMgr::setParameter(int compId, QString paramName, QVariant value, bool forceSend)
329
{
330
    if (paramName.isEmpty()) {
331 332 333 334 335
        return;
    }

    double dblValue = value.toDouble();

336 337
    if (paramDataModel->isValueLessThanParamMin(paramName,dblValue)) {
        setParameterStatusMsg(tr("REJ. %1, %2 < min").arg(paramName).arg(dblValue),
tstellanova's avatar
tstellanova committed
338 339
                              ParamCommsStatusLevel_Error
                              );
340 341
        return;
    }
342 343
    if (paramDataModel->isValueGreaterThanParamMax(paramName,dblValue)) {
        setParameterStatusMsg(tr("REJ. %1, %2 > max").arg(paramName).arg(dblValue),
tstellanova's avatar
tstellanova committed
344 345
                              ParamCommsStatusLevel_Error
                              );
346 347
        return;
    }
348

349 350 351 352 353 354 355 356 357 358
	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;
		}
	}
359

360 361 362
    emitPendingParameterCommit(compId, paramName, value);

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

364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382
    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();
383 384 385
    }


386 387
    if (missReadCount > 0 || missWriteCount > 0) {
        lastSilenceTimerReset = QGC::groundTimeMilliseconds();
tstellanova's avatar
tstellanova committed
388 389 390
        if (0 == lastReceiveTime) {
            lastReceiveTime = lastSilenceTimerReset;
        }
391 392
        // We signal this to ourselves so timer is started on the right thread
        emit _startSilenceTimer();
393
    }
394
    else {
395
        //all parameters have been received, broadcast to UI
396
        qCDebug(UASParameterCommsMgrLog) << "emitting parameterListUpToDate";
397 398
        emit parameterListUpToDate();
        resetAfterListReceive();
399
        emit _stopSilenceTimer(); // Stop timer on our thread;
tstellanova's avatar
tstellanova committed
400
        lastReceiveTime = 0;
401 402
    }

403 404


405 406
}

407

tstellanova's avatar
tstellanova committed
408
void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level)
409
{
Lorenz Meier's avatar
Lorenz Meier committed
410
    //qDebug() << "parameterStatusMsg: " << msg;
tstellanova's avatar
tstellanova committed
411
    emit parameterStatusMsgUpdated(msg,level);
412
}
tstellanova's avatar
tstellanova committed
413 414 415

void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value)
{
416
    qCDebug(UASParameterCommsMgrLog) << "Received parameter update for:" << paramName << "count" << paramCount << "index" << paramId << "value" << value;
417

418
    Q_UNUSED(uas); //this object is assigned to one UAS only
419
    lastReceiveTime = QGC::groundTimeMilliseconds();
Lorenz Meier's avatar
Lorenz Meier committed
420
    // qDebug() << "compId" << compId << "receivedParameterUpdate:" << paramName;
421

422
    //notify the data model that we have an updated param
423
    paramDataModel->handleParamUpdate(compId,paramName,value);
tstellanova's avatar
tstellanova committed
424 425


426 427 428 429 430 431 432
    // 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>());
    }
433

434
    QSet<int>* compMissingReads =  readsWaiting.value(compId);
tstellanova's avatar
tstellanova committed
435 436
    // List mode is different from single parameter transfers
    if (transmissionListMode) {
437 438
        // Only accept the list size once on the first packet from each component
        if (!knownParamListSize.contains(compId)) {
tstellanova's avatar
tstellanova committed
439
            // Mark list size as known
440
            knownParamListSize.insert(compId,paramCount);
tstellanova's avatar
tstellanova committed
441

442 443
            //remove our placeholder read request for all params
            readsWaiting.value(0)->remove(0);
tstellanova's avatar
tstellanova committed
444

445
            qCDebug(UASParameterCommsMgrLog) << "receivedParameterUpdate: Mark all parameters as missing: " << paramCount;
446 447
            for (int i = 1; i < paramCount; ++i) { //param Id 0 is  "all parameters" and not valid
                compMissingReads->insert(i);
tstellanova's avatar
tstellanova committed
448 449
            }
        }
450
        
Don Gagne's avatar
Don Gagne committed
451
        emit parameterListProgress((float)paramId / (float)paramCount);
452 453 454
        if (paramId == paramCount) {
            emit parameterListProgress(0.0f);
        }
tstellanova's avatar
tstellanova committed
455 456
    }

457

tstellanova's avatar
tstellanova committed
458
    // Mark this parameter as received in read list
459 460
    compMissingReads->remove(paramId);

tstellanova's avatar
tstellanova committed
461 462 463

    bool justWritten = false;
    bool writeMismatch = false;
464

tstellanova's avatar
tstellanova committed
465
    // Mark this parameter as received in write ACK list
466 467
    QMap<QString, QVariant>* compMissingWrites = writesWaiting.value(compId);
    if (!compMissingWrites) {
468
        //we sometimes send a write request on compId 0 and get a response on a nonzero compId eg 50
469
        compMissingWrites = writesWaiting.value(0);
470
    }
471
    if (compMissingWrites && compMissingWrites->contains(paramName)) {
tstellanova's avatar
tstellanova committed
472
        justWritten = true;
473
        if (compMissingWrites->value(paramName) != value) {
tstellanova's avatar
tstellanova committed
474 475
            writeMismatch = true;
        }
476
        compMissingWrites->remove(paramName);
tstellanova's avatar
tstellanova committed
477 478 479
    }


480
    if (justWritten) {
481
        int waitingWritesCount = compMissingWrites->count();
482
        if (!writeMismatch) {
483 484 485 486 487 488
            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));
489 490 491 492
                if (persistParamsAfterSend) {
                    writeParamsToPersistentStorage();
                    persistParamsAfterSend = false;
                }
493 494 495 496
            }
        }
        else  {
            // Mismatch, tell user
497
            setParameterStatusMsg(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(paramName).arg(compMissingWrites->value(paramName).toDouble()).arg(value.toDouble()),
498 499
                                  ParamCommsStatusLevel_Warning);
        }
tstellanova's avatar
tstellanova committed
500 501
    }
    else {
502 503 504
        int waitingReadsCount = compMissingReads->count();

        if (0 == waitingReadsCount) {
tstellanova's avatar
tstellanova committed
505 506 507 508 509 510
            // Transmission done
            QTime time = QTime::currentTime();
            QString timeString = time.toString();
            setParameterStatusMsg(tr("All received. (updated at %1)").arg(timeString));
        }
        else {
511
            // Waiting to receive more
512
            QString val = QString("%1").arg(value.toFloat(), 5, 'f', 1, QChar(' '));
513 514
            setParameterStatusMsg(tr("OK: %1 %2 (%3/%4)").arg(paramName).arg(val).arg(paramCount-waitingReadsCount).arg(paramCount),
                                  ParamCommsStatusLevel_OK);
tstellanova's avatar
tstellanova committed
515 516 517
        }
    }

518 519 520
    updateSilenceTimer();


tstellanova's avatar
tstellanova committed
521 522 523 524 525 526 527
}


void UASParameterCommsMgr::writeParamsToPersistentStorage()
{
    if (mav) {
        mav->writeParametersToStorage(); //TODO track timeout, retransmit etc?
528
        persistParamsAfterSend = false; //done
tstellanova's avatar
tstellanova committed
529 530 531 532
    }
}


533
void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent, bool forceSend)
tstellanova's avatar
tstellanova committed
534
{
535 536
    persistParamsAfterSend |= copyToPersistent;

tstellanova's avatar
tstellanova committed
537 538
    // Iterate through all components, through all pending parameters and send them to UAS
    int parametersSent = 0;
539
    QMap<int, QMap<QString, QVariant>*>* changedValues = paramDataModel->getAllPendingParams();
tstellanova's avatar
tstellanova committed
540
    QMap<int, QMap<QString, QVariant>*>::iterator i;
541
    for (i = changedValues->begin(); i != changedValues->end(); ++i) {
tstellanova's avatar
tstellanova committed
542
        // Iterate through the parameters of the component
tstellanova's avatar
tstellanova committed
543 544 545 546 547 548
        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) {
549
            setParameter(compId, j.key(), j.value(), forceSend);
tstellanova's avatar
tstellanova committed
550
            parametersSent++;
tstellanova's avatar
tstellanova committed
551 552 553 554
        }
    }

    // Change transmission status if necessary
555
    if (0 == parametersSent) {
tstellanova's avatar
tstellanova committed
556
        setParameterStatusMsg(tr("No transmission: No changed values."),ParamCommsStatusLevel_Warning);
557 558
    }
    else {
tstellanova's avatar
tstellanova committed
559
        setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent));
560
        qCDebug(UASParameterCommsMgrLog) << "Pending parameters now:" << paramDataModel->countPendingParams();
tstellanova's avatar
tstellanova committed
561
    }
562 563 564


    updateSilenceTimer();
tstellanova's avatar
tstellanova committed
565 566
}

567 568
UASParameterCommsMgr::~UASParameterCommsMgr()
{
569
    silenceTimer.stop();
570 571 572

    QString ptrStr;
    ptrStr.sprintf("%8p", this);
573
    qCDebug(UASParameterCommsMgrLog) <<  "UASParameterCommsMgr destructor: " << ptrStr ;
574

575 576
}

577 578 579 580 581 582 583 584 585
void UASParameterCommsMgr::_startSilenceTimerOnThisThread(void)
{
    silenceTimer.start(silenceTimeout);
}

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