QGCVehicleConfig.cc 21.6 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

#include <QTimer>
11 12 13
#include <QDir>
#include <QXmlStreamReader>
#include <QMessageBox>
14

15
#include "QGCVehicleConfig.h"
16
#include "UASManager.h"
17
#include "QGC.h"
18
#include "QGCToolWidget.h"
19 20 21 22
#include "ui_QGCVehicleConfig.h"

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

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

44 45
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

46
    ui->rcCalibrationButton->setCheckable(true);
47 48
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
    connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
49
    connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70
    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)));
71 72 73 74 75

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

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

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

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
85 86 87 88 89 90
}

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

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

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

113 114
void QGCVehicleConfig::setTrimPositions()
{
Lorenz Meier's avatar
Lorenz Meier committed
115 116 117 118 119 120
    // 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
121
    else if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100)
Lorenz Meier's avatar
Lorenz Meier committed
122 123 124
    {
        rcTrim[rcMapping[3]] = rcMax[rcMapping[3]];   // throttle
    }
125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141
    else
    {

        // Reject
        QMessageBox msgBox;
        msgBox.setText(tr("Throttle Stick Trim Position Invalid"));
        msgBox.setInformativeText(tr("The throttle stick is not in the min position. Please set it to the minimum value"));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        (void)msgBox.exec();
    }

    // Set trim for roll, pitch, yaw, throttle
    rcTrim[rcMapping[0]] = rcValue[rcMapping[0]]; // roll
    rcTrim[rcMapping[1]] = rcValue[rcMapping[1]]; // pitch
    rcTrim[rcMapping[2]] = rcValue[rcMapping[2]]; // yaw

142 143 144 145
    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
146 147 148 149 150 151 152
}

void QGCVehicleConfig::detectChannelInversion()
{

}

153 154 155
void QGCVehicleConfig::startCalibrationRC()
{
    ui->rcTypeComboBox->setEnabled(false);
156
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
157
    resetCalibrationRC();
158
    calibrationEnabled = true;
159 160 161 162
}

void QGCVehicleConfig::stopCalibrationRC()
{
163
    calibrationEnabled = false;
164
    ui->rcTypeComboBox->setEnabled(true);
165
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
166 167 168 169 170 171 172 173 174 175 176 177 178 179
}

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)));
180 181 182 183 184

        foreach (QGCToolWidget* tool, toolWidgets)
        {
            delete tool;
        }
185
        toolWidgets.clear();
186 187
    }

188 189 190
    // Reset current state
    resetCalibrationRC();

191 192
    chanCount = 0;

193 194
    // Connect new system
    mav = active;
195 196 197 198
    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)));
199 200 201 202 203 204 205 206 207 208 209 210 211

    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);
212 213
    } else {
        delete tool;
214
    }
215

216 217 218 219 220 221
    // 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);
222 223
    } else {
        delete tool;
224 225 226 227 228 229 230 231
    }

    // 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);
232 233
    } else {
        delete tool;
234 235 236 237 238 239 240 241
    }

    // 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);
242 243
    } else {
        delete tool;
244 245 246 247 248 249 250 251
    }

    // 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);
252 253
    } else {
        delete tool;
254 255 256
    }

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
257 258 259 260 261 262
}

void QGCVehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
263 264
        rcMin[i] = 1200;
        rcMax[i] = 1800;
265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282
    }
}

/**
 * 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

283
    for (unsigned int i = 0; i < chanCount; ++i)
284
    {
285
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
Lorenz Meier's avatar
Lorenz Meier committed
286
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
287
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
288
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
289
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
290
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
291 292 293
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
294 295 296
    }

    // Write mappings
297 298 299 300
    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);
301
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
302
    QGC::SLEEP::usleep(50000);
303
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
304 305 306 307 308 309 310 311 312
    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);
313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328
}

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
329
        mav->requestParameter(0, minTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
330
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
331
        mav->requestParameter(0, trimTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
332
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
333
        mav->requestParameter(0, maxTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
334
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
335
        mav->requestParameter(0, revTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
336
        QGC::SLEEP::usleep(5000);
337 338 339 340 341 342 343
    }
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
344
    mav->writeParametersToStorage();
345 346 347 348
}

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

Bryant's avatar
Bryant committed
353
    if (chan + 1 > (int)chanCount) {
354 355 356 357 358 359 360 361 362 363 364 365 366 367
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
368 369
    }

370 371 372
    // Raw value
    rcValue[chan] = val;

373 374 375 376
    // Normalized value
    float normalized;

    if (val >= rcTrim[chan])
377
    {
378
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
379
    }
380 381 382 383 384 385 386 387 388
    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;
389

390 391 392
    if (chan == rcMapping[0])
    {
        // ROLL
393
        rcRoll = normalized;
394
    }
395
    if (chan == rcMapping[1])
396 397
    {
        // PITCH
398
        rcPitch = normalized;
399
    }
400
    if (chan == rcMapping[2])
401
    {
402
        rcYaw = normalized;
403
    }
404
    if (chan == rcMapping[3])
405 406
    {
        // THROTTLE
407 408 409 410
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
411
        }
412 413

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
414
    }
415
    if (chan == rcMapping[4])
416 417
    {
        // MODE SWITCH
418
        rcMode = normalized;
419
    }
420
    if (chan == rcMapping[5])
421 422
    {
        // AUX1
423
        rcAux1 = normalized;
424
    }
425
    if (chan == rcMapping[6])
426 427
    {
        // AUX2
428
        rcAux2 = normalized;
429
    }
430
    if (chan == rcMapping[7])
431 432
    {
        // AUX3
433
        rcAux3 = normalized;
434 435 436 437
    }

    changed = true;

438
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
439 440
}

441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473
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;
    }
}

474 475 476 477
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493

    // 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
494
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
495
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
496
        if (ok && (index >= 0) && (index < chanMax))
497 498 499 500 501 502 503
        {
            rcMin[index] = value.toInt();
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
504
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
505
        if (ok && (index >= 0) && (index < chanMax))
506 507 508 509 510 511 512
        {
            rcMax[index] = value.toInt();
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
513
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
514
        if (ok && (index >= 0) && (index < chanMax))
515 516 517 518 519 520 521
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
522
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
523
        if (ok && (index >= 0) && (index < chanMax))
524 525
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
526
            updateInvertedCheckboxes(index);
527 528 529 530 531 532 533 534
        }
    }

//        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);
//    }

535 536 537 538 539 540 541 542
    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();
    }
543 544 545 546

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

    if (parameterName.contains("RC_MAP_ROLL")) {
547 548
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
549 550 551
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
552 553
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
554 555 556
    }

    if (parameterName.contains("RC_MAP_YAW")) {
557 558
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
559 560 561
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
562 563
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
564 565 566
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
567 568
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
569 570 571
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
572 573
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
574 575 576
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
577
        rcMapping[6] = value.toInt() - 1;
578
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
579 580 581
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
582
        rcMapping[7] = value.toInt() - 1;
583
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
584 585 586 587 588
    }

    // Scaling

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

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

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

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
601
        rcScaling[3] = value.toFloat();
602 603 604
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
605
        rcScaling[4] = value.toFloat();
606 607 608
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
609
        rcScaling[5] = value.toFloat();
610 611 612
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
613
        rcScaling[6] = value.toFloat();
614 615 616
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
617
        rcScaling[7] = value.toFloat();
618
    }
619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658
}

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)
    {
659 660
        if (rc_mode == RC_MODE_1)
        {
661 662 663 664
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
665 666 667
        }
        else if (rc_mode == RC_MODE_2)
        {
668 669 670 671
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
672 673 674
        }
        else if (rc_mode == RC_MODE_3)
        {
675 676 677 678
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
679 680 681
        }
        else if (rc_mode == RC_MODE_4)
        {
682 683 684 685 686 687
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
        }

688 689 690 691
        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(' ')));
692 693

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

696
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
697
            ui->aux1Slider->setValue(rcAux1 * 50 + 50);
698
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
699 700 701 702
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

703
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
704
            ui->aux2Slider->setValue(rcAux2 * 50 + 50);
705
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
706 707 708 709
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

710
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
711
            ui->aux3Slider->setValue(rcAux3 * 50 + 50);
712
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
713 714
        } else {
            ui->chanLabel_8->setText(tr("---"));
715 716
        }

717 718 719
        changed = false;
    }
}