QGCVehicleConfig.cc 21.1 KB
Newer Older
Bryant's avatar
Bryant committed
1 2 3 4 5 6
// On Windows (for VS2010) stdint.h contains the limits normally contained in limits.h
// It also needs the __STDC_LIMIT_MACROS macro defined in order to include them (done
// in qgroundcontrol.pri).
#ifdef WIN32
#include <stdint.h>
#else
7
#include <limits.h>
Bryant's avatar
Bryant committed
8
#endif
9 10 11

#include <QTimer>

12
#include "QGCVehicleConfig.h"
13
#include "UASManager.h"
14
#include "QGC.h"
15
#include "QGCToolWidget.h"
16 17 18 19
#include "ui_QGCVehicleConfig.h"

QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
    QWidget(parent),
20
    mav(NULL),
21
    chanCount(0),
22 23 24 25 26 27 28 29
    rcRoll(0.0f),
    rcPitch(0.0f),
    rcYaw(0.0f),
    rcThrottle(0.0f),
    rcMode(0.0f),
    rcAux1(0.0f),
    rcAux2(0.0f),
    rcAux3(0.0f),
30 31
    changed(true),
    rc_mode(RC_MODE_2),
32
    calibrationEnabled(false),
33 34
    ui(new Ui::QGCVehicleConfig)
{
35
    setObjectName("QGC_VEHICLECONFIG");
36
    ui->setupUi(this);
37 38 39 40

    requestCalibrationRC();
    if (mav) mav->requestParameter(0, "RC_TYPE");

41 42
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

43
    ui->rcCalibrationButton->setCheckable(true);
44 45
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
    connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
46
    connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67
    connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));

    /* Connect RC mapping assignments */
    connect(ui->rollSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setRollChan(int)));
    connect(ui->pitchSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setPitchChan(int)));
    connect(ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYawChan(int)));
    connect(ui->throttleSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setThrottleChan(int)));
    connect(ui->modeSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setModeChan(int)));
    connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int)));
    connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(int)));
    connect(ui->aux3SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux3Chan(int)));

    // Connect RC reverse assignments
    connect(ui->invertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setRollInverted(bool)));
    connect(ui->invertCheckBox_2, SIGNAL(clicked(bool)), this, SLOT(setPitchInverted(bool)));
    connect(ui->invertCheckBox_3, SIGNAL(clicked(bool)), this, SLOT(setYawInverted(bool)));
    connect(ui->invertCheckBox_4, SIGNAL(clicked(bool)), this, SLOT(setThrottleInverted(bool)));
    connect(ui->invertCheckBox_5, SIGNAL(clicked(bool)), this, SLOT(setModeInverted(bool)));
    connect(ui->invertCheckBox_6, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool)));
    connect(ui->invertCheckBox_7, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool)));
    connect(ui->invertCheckBox_8, SIGNAL(clicked(bool)), this, SLOT(setAux3Inverted(bool)));
68 69 70 71 72

    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));

    setActiveUAS(UASManager::instance()->getActiveUAS());

73
    for (unsigned int i = 0; i < chanMax; i++)
74
    {
75
        rcValue[i] = UINT16_MAX;
76
        rcMapping[i] = i;
77 78 79 80 81
    }

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
82 83 84 85 86 87
}

QGCVehicleConfig::~QGCVehicleConfig()
{
    delete ui;
}
88

89 90 91 92 93 94 95 96
void QGCVehicleConfig::setRCModeIndex(int newRcMode)
{
    if (newRcMode > 0 && newRcMode < 5)
    {
        rc_mode = (enum RC_MODE) (newRcMode+1);
        changed = true;
    }
}
97 98 99 100 101 102 103 104 105 106 107 108 109

void QGCVehicleConfig::toggleCalibrationRC(bool enabled)
{
    if (enabled)
    {
        startCalibrationRC();
    }
    else
    {
        stopCalibrationRC();
    }
}

110 111 112
void QGCVehicleConfig::setTrimPositions()
{
    // Set trim for roll, pitch, yaw, throttle
113 114 115
    rcTrim[rcMapping[0]] = rcValue[rcMapping[0]]; // roll
    rcTrim[rcMapping[1]] = rcValue[rcMapping[1]]; // pitch
    rcTrim[rcMapping[2]] = rcValue[rcMapping[2]]; // yaw
Lorenz Meier's avatar
Lorenz Meier committed
116 117 118 119 120 121 122 123 124 125
    // Set trim to min if stick is close to min
    if (abs(rcValue[rcMapping[3]] - rcMin[rcMapping[3]]) < 100)
    {
        rcTrim[rcMapping[3]] = rcMin[rcMapping[3]];   // throttle
    }
    // Set trim to max if stick is close to max
    if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100)
    {
        rcTrim[rcMapping[3]] = rcMax[rcMapping[3]];   // throttle
    }
126 127 128 129
    rcTrim[rcMapping[4]] = ((rcMax[rcMapping[4]] - rcMin[rcMapping[4]]) / 2.0f) + rcMin[rcMapping[4]];   // mode sw
    rcTrim[rcMapping[5]] = ((rcMax[rcMapping[5]] - rcMin[rcMapping[5]]) / 2.0f) + rcMin[rcMapping[5]];   // aux 1
    rcTrim[rcMapping[6]] = ((rcMax[rcMapping[6]] - rcMin[rcMapping[6]]) / 2.0f) + rcMin[rcMapping[6]];   // aux 2
    rcTrim[rcMapping[7]] = ((rcMax[rcMapping[7]] - rcMin[rcMapping[7]]) / 2.0f) + rcMin[rcMapping[7]];   // aux 3
130 131 132 133 134 135 136
}

void QGCVehicleConfig::detectChannelInversion()
{

}

137 138 139
void QGCVehicleConfig::startCalibrationRC()
{
    ui->rcTypeComboBox->setEnabled(false);
140
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
141
    resetCalibrationRC();
142
    calibrationEnabled = true;
143 144 145 146
}

void QGCVehicleConfig::stopCalibrationRC()
{
147
    calibrationEnabled = false;
148
    ui->rcTypeComboBox->setEnabled(true);
149
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
150 151 152 153 154 155 156 157 158 159 160 161 162 163
}

void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
    // Do nothing if system is the same or NULL
    if ((active == NULL) || mav == active) return;

    if (mav)
    {
        // Disconnect old system
        disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
                   SLOT(remoteControlChannelRawChanged(int,float)));
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
                   SLOT(parameterChanged(int,int,QString,QVariant)));
164 165 166 167 168

        foreach (QGCToolWidget* tool, toolWidgets)
        {
            delete tool;
        }
169
        toolWidgets.clear();
170 171
    }

172 173 174
    // Reset current state
    resetCalibrationRC();

175 176
    chanCount = 0;

177 178
    // Connect new system
    mav = active;
179 180 181 182
    connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
               SLOT(remoteControlChannelRawChanged(int,float)));
    connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
               SLOT(parameterChanged(int,int,QString,QVariant)));
183 184 185 186 187 188 189 190 191 192 193 194 195

    mav->requestParameters();

    QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/";

    QGCToolWidget* tool;

    // Load calibration
    tool = new QGCToolWidget("", this);
    if (tool->loadSettings(defaultsDir + "px4_calibration.qgw", false))
    {
        toolWidgets.append(tool);
        ui->sensorLayout->addWidget(tool);
196 197
    } else {
        delete tool;
198
    }
199

200 201 202 203 204 205
    // Load multirotor attitude pid
    tool = new QGCToolWidget("", this);
    if (tool->loadSettings(defaultsDir + "px4_mc_attitude_pid_params.qgw", false))
    {
        toolWidgets.append(tool);
        ui->multiRotorAttitudeLayout->addWidget(tool);
206 207
    } else {
        delete tool;
208 209 210 211 212 213 214 215
    }

    // Load multirotor position pid
    tool = new QGCToolWidget("", this);
    if (tool->loadSettings(defaultsDir + "px4_mc_position_pid_params.qgw", false))
    {
        toolWidgets.append(tool);
        ui->multiRotorPositionLayout->addWidget(tool);
216 217
    } else {
        delete tool;
218 219 220 221 222 223 224 225
    }

    // Load fixed wing attitude pid
    tool = new QGCToolWidget("", this);
    if (tool->loadSettings(defaultsDir + "px4_fw_attitude_pid_params.qgw", false))
    {
        toolWidgets.append(tool);
        ui->fixedWingAttitudeLayout->addWidget(tool);
226 227
    } else {
        delete tool;
228 229 230 231 232 233 234 235
    }

    // Load fixed wing position pid
    tool = new QGCToolWidget("", this);
    if (tool->loadSettings(defaultsDir + "px4_fw_position_pid_params.qgw", false))
    {
        toolWidgets.append(tool);
        ui->fixedWingPositionLayout->addWidget(tool);
236 237
    } else {
        delete tool;
238 239 240
    }

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
241 242 243 244 245 246
}

void QGCVehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
247 248
        rcMin[i] = 1200;
        rcMax[i] = 1800;
249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266
    }
}

/**
 * Sends the RC calibration to the vehicle and stores it in EEPROM
 */
void QGCVehicleConfig::writeCalibrationRC()
{
    if (!mav) return;

    QString minTpl("RC%1_MIN");
    QString maxTpl("RC%1_MAX");
    QString trimTpl("RC%1_TRIM");
    QString revTpl("RC%1_REV");

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

267
    for (unsigned int i = 0; i < chanCount; ++i)
268
    {
269
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
Lorenz Meier's avatar
Lorenz Meier committed
270
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
271
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
272
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
273
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
274
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
275 276 277
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
278 279 280
    }

    // Write mappings
281 282 283 284
    mav->setParameter(0, "RC_MAP_ROLL", (int32_t)(rcMapping[0]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_PITCH", (int32_t)(rcMapping[1]+1));
    QGC::SLEEP::usleep(50000);
285
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
286
    QGC::SLEEP::usleep(50000);
287
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
288 289 290 291 292 293 294 295 296
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_MODE_SW", (int32_t)(rcMapping[4]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_AUX1", (int32_t)(rcMapping[5]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_AUX2", (int32_t)(rcMapping[6]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_AUX3", (int32_t)(rcMapping[7]+1));
    QGC::SLEEP::usleep(50000);
297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312
}

void QGCVehicleConfig::requestCalibrationRC()
{
    if (!mav) return;

    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

    for (unsigned int i = 0; i < chanMax; ++i)
    {
Lorenz Meier's avatar
Lorenz Meier committed
313
        mav->requestParameter(0, minTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
314
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
315
        mav->requestParameter(0, trimTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
316
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
317
        mav->requestParameter(0, maxTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
318
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
319
        mav->requestParameter(0, revTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
320
        QGC::SLEEP::usleep(5000);
321 322 323 324 325 326 327
    }
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
328
    mav->writeParametersToStorage();
329 330 331 332
}

void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
{
333 334
    // Check if index and values are sane
    if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax || val < 500 || val > 2500)
335 336
        return;

Bryant's avatar
Bryant committed
337
    if (chan + 1 > (int)chanCount) {
338 339 340 341 342 343 344 345 346 347 348 349 350 351
        chanCount = chan+1;
    }

    // Update calibration data
    if (calibrationEnabled) {
        if (val < rcMin[chan])
        {
            rcMin[chan] = val;
        }

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
352 353
    }

354 355 356
    // Raw value
    rcValue[chan] = val;

357 358 359 360
    // Normalized value
    float normalized;

    if (val >= rcTrim[chan])
361
    {
362
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
363
    }
364 365 366 367 368 369 370 371 372
    else
    {
        normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]);
    }

    // Bound
    normalized = qBound(-1.0f, normalized, 1.0f);
    // Invert
    normalized = (rcRev[chan]) ? -1.0f*normalized : normalized;
373

374 375 376
    if (chan == rcMapping[0])
    {
        // ROLL
377
        rcRoll = normalized;
378
    }
379
    if (chan == rcMapping[1])
380 381
    {
        // PITCH
382
        rcPitch = normalized;
383
    }
384
    if (chan == rcMapping[2])
385
    {
386
        rcYaw = normalized;
387
    }
388
    if (chan == rcMapping[3])
389 390
    {
        // THROTTLE
391 392 393 394
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
395
        }
396 397

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
398
    }
399
    if (chan == rcMapping[4])
400 401
    {
        // MODE SWITCH
402
        rcMode = normalized;
403
    }
404
    if (chan == rcMapping[5])
405 406
    {
        // AUX1
407
        rcAux1 = normalized;
408
    }
409
    if (chan == rcMapping[6])
410 411
    {
        // AUX2
412
        rcAux2 = normalized;
413
    }
414
    if (chan == rcMapping[7])
415 416
    {
        // AUX3
417
        rcAux3 = normalized;
418 419 420 421
    }

    changed = true;

422
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
423 424
}

425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457
void QGCVehicleConfig::updateInvertedCheckboxes(int index)
{
    unsigned int mapindex = rcMapping[index];

    switch (mapindex)
    {
    case 0:
        ui->invertCheckBox->setChecked(rcRev[index]);
        break;
    case 1:
        ui->invertCheckBox_2->setChecked(rcRev[index]);
        break;
    case 2:
        ui->invertCheckBox_3->setChecked(rcRev[index]);
        break;
    case 3:
        ui->invertCheckBox_4->setChecked(rcRev[index]);
        break;
    case 4:
        ui->invertCheckBox_5->setChecked(rcRev[index]);
        break;
    case 5:
        ui->invertCheckBox_6->setChecked(rcRev[index]);
        break;
    case 6:
        ui->invertCheckBox_7->setChecked(rcRev[index]);
        break;
    case 7:
        ui->invertCheckBox_8->setChecked(rcRev[index]);
        break;
    }
}

458 459 460 461
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477

    // Channel calibration values
    QRegExp minTpl("RC?_MIN");
    minTpl.setPatternSyntax(QRegExp::Wildcard);
    QRegExp maxTpl("RC?_MAX");
    maxTpl.setPatternSyntax(QRegExp::Wildcard);
    QRegExp trimTpl("RC?_TRIM");
    trimTpl.setPatternSyntax(QRegExp::Wildcard);
    QRegExp revTpl("RC?_REV");
    revTpl.setPatternSyntax(QRegExp::Wildcard);

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

    if (minTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
478
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
479
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
480
        if (ok && (index >= 0) && (index < chanMax))
481 482 483 484 485 486 487
        {
            rcMin[index] = value.toInt();
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
488
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
489
        if (ok && (index >= 0) && (index < chanMax))
490 491 492 493 494 495 496
        {
            rcMax[index] = value.toInt();
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
497
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
498
        if (ok && (index >= 0) && (index < chanMax))
499 500 501 502 503 504 505
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
506
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
507
        if (ok && (index >= 0) && (index < chanMax))
508 509
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
510
            updateInvertedCheckboxes(index);
511 512 513 514 515 516 517 518
        }
    }

//        mav->setParameter(0, trimTpl.arg(i), rcTrim[i]);
//        mav->setParameter(0, maxTpl.arg(i), rcMax[i]);
//        mav->setParameter(0, revTpl.arg(i), (rcRev[i]) ? -1 : 1);
//    }

519 520 521 522 523 524 525 526
    if (rcTypeUpdateRequested > 0 && parameterName == QString("RC_TYPE"))
    {
        rcTypeUpdateRequested = 0;
        updateStatus(tr("Received RC type update, setting parameters based on model."));
        rcType = value.toInt();
        // Request all other parameters as well
        requestCalibrationRC();
    }
527 528 529 530

    // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3

    if (parameterName.contains("RC_MAP_ROLL")) {
531 532
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
533 534 535
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
536 537
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
538 539 540
    }

    if (parameterName.contains("RC_MAP_YAW")) {
541 542
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
543 544 545
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
546 547
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
548 549 550
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
551 552
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
553 554 555
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
556 557
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
558 559 560
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
561
        rcMapping[6] = value.toInt() - 1;
562
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
563 564 565
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
566
        rcMapping[7] = value.toInt() - 1;
567
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
568 569 570 571 572
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
573
        rcScaling[0] = value.toFloat();
574 575 576
    }

    if (parameterName.contains("RC_SCALE_PITCH")) {
577
        rcScaling[1] = value.toFloat();
578 579 580
    }

    if (parameterName.contains("RC_SCALE_YAW")) {
581
        rcScaling[2] = value.toFloat();
582 583 584
    }

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
585
        rcScaling[3] = value.toFloat();
586 587 588
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
589
        rcScaling[4] = value.toFloat();
590 591 592
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
593
        rcScaling[5] = value.toFloat();
594 595 596
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
597
        rcScaling[6] = value.toFloat();
598 599 600
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
601
        rcScaling[7] = value.toFloat();
602
    }
603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642
}

void QGCVehicleConfig::updateStatus(const QString& str)
{
    ui->statusLabel->setText(str);
    ui->statusLabel->setStyleSheet("");
}

void QGCVehicleConfig::updateError(const QString& str)
{
    ui->statusLabel->setText(str);
    ui->statusLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name()));
}

void QGCVehicleConfig::setRCType(int type)
{
    if (!mav) return;

    // XXX TODO Add handling of RC_TYPE vs non-RC_TYPE here

    mav->setParameter(0, "RC_TYPE", type);
    rcTypeUpdateRequested = QGC::groundTimeMilliseconds();
    QTimer::singleShot(rcTypeTimeout+100, this, SLOT(checktimeOuts()));
}

void QGCVehicleConfig::checktimeOuts()
{
    if (rcTypeUpdateRequested > 0)
    {
        if (QGC::groundTimeMilliseconds() - rcTypeUpdateRequested > rcTypeTimeout)
        {
            updateError(tr("Setting remote control timed out - is the system connected?"));
        }
    }
}

void QGCVehicleConfig::updateView()
{
    if (changed)
    {
643 644
        if (rc_mode == RC_MODE_1)
        {
645 646 647 648
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
649 650 651
        }
        else if (rc_mode == RC_MODE_2)
        {
652 653 654 655
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
656 657 658
        }
        else if (rc_mode == RC_MODE_3)
        {
659 660 661 662
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
663 664 665
        }
        else if (rc_mode == RC_MODE_4)
        {
666 667 668 669 670 671
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
        }

672 673 674 675
        ui->chanLabel->setText(QString("%1/%2").arg(rcValue[rcMapping[0]]).arg(rcRoll, 5, 'f', 2, QChar(' ')));
        ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[rcMapping[1]]).arg(rcPitch, 5, 'f', 2, QChar(' ')));
        ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[rcMapping[2]]).arg(rcYaw, 5, 'f', 2, QChar(' ')));
        ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[rcMapping[3]]).arg(rcThrottle, 5, 'f', 2, QChar(' ')));
676 677

        ui->modeSwitchSlider->setValue(rcMode * 50 + 50);
678
        ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[rcMapping[4]]).arg(rcMode, 5, 'f', 2, QChar(' ')));
679

680
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
681
            ui->aux1Slider->setValue(rcAux1 * 50 + 50);
682
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
683 684 685 686
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

687
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
688
            ui->aux2Slider->setValue(rcAux2 * 50 + 50);
689
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
690 691 692 693
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

694
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
695
            ui->aux3Slider->setValue(rcAux3 * 50 + 50);
696
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
697 698
        } else {
            ui->chanLabel_8->setText(tr("---"));
699 700
        }

701 702 703
        changed = false;
    }
}