QGCVehicleConfig.cc 50.8 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
    doneLoadingConfig = false;
39 40 41
    systemTypeToParamMap["FIXED_WING"] = new QMap<QString,QGCToolWidget*>();
    systemTypeToParamMap["QUADROTOR"] = new QMap<QString,QGCToolWidget*>();
    systemTypeToParamMap["GROUND_ROVER"] = new QMap<QString,QGCToolWidget*>();
42
    systemTypeToParamMap["BOAT"] = new QMap<QString,QGCToolWidget*>();
43
    libParamToWidgetMap = new QMap<QString,QGCToolWidget*>();
44

45
    setObjectName("QGC_VEHICLECONFIG");
46
    ui->setupUi(this);
47 48 49 50

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

51 52
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

53
    ui->rcCalibrationButton->setCheckable(true);
54 55
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
    connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
56
    connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77
    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)));
78 79 80 81 82

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

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

83
    for (unsigned int i = 0; i < chanMax; i++)
84
    {
85
        rcValue[i] = UINT16_MAX;
86
        rcMapping[i] = i;
87 88 89 90 91
    }

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
92 93 94 95 96 97
}

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

99 100 101 102 103 104 105 106
void QGCVehicleConfig::setRCModeIndex(int newRcMode)
{
    if (newRcMode > 0 && newRcMode < 5)
    {
        rc_mode = (enum RC_MODE) (newRcMode+1);
        changed = true;
    }
}
107 108 109 110 111 112 113 114 115 116 117 118 119

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

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

149 150 151 152
    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
153 154 155 156 157 158 159
}

void QGCVehicleConfig::detectChannelInversion()
{

}

160 161 162
void QGCVehicleConfig::startCalibrationRC()
{
    ui->rcTypeComboBox->setEnabled(false);
163
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
164
    resetCalibrationRC();
165
    calibrationEnabled = true;
166 167 168 169
}

void QGCVehicleConfig::stopCalibrationRC()
{
170
    calibrationEnabled = false;
171
    ui->rcTypeComboBox->setEnabled(true);
172
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
173 174
}

175
void QGCVehicleConfig::loadQgcConfig(bool primary)
176
{
177 178 179 180 181 182
    QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower());
    QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets");
    QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets");
    if (!autopilotdir.exists("general"))
    {
     //TODO: Throw some kind of error here. There is no general configuration directory
183
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
184 185 186 187
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
188
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
189
    }
190 191
    QGCToolWidget *tool;
    bool left = true;
192 193 194 195 196 197 198 199 200 201 202 203
    foreach (QString file,generaldir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
            tool = new QGCToolWidget("", this);
            if (tool->loadSettings(generaldir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
                //ui->sensorLayout->addWidget(tool);
                QGroupBox *box = new QGroupBox(this);
                box->setTitle(tool->objectName());
                box->setLayout(new QVBoxLayout());
                box->layout()->addWidget(tool);
204
                if (left)
205
                {
206 207 208 209 210 211 212
                    left = false;
                    ui->leftGeneralLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->rightGeneralLayout->addWidget(box);
213
                }
214 215 216 217 218
            } else {
                delete tool;
            }
        }
    }
219
    left = true;
220 221 222 223 224 225 226 227 228 229 230 231
    foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
            tool = new QGCToolWidget("", this);
            if (tool->loadSettings(vehicledir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
                //ui->sensorLayout->addWidget(tool);
                QGroupBox *box = new QGroupBox(this);
                box->setTitle(tool->objectName());
                box->setLayout(new QVBoxLayout());
                box->layout()->addWidget(tool);
232
                if (left)
233
                {
234 235 236 237 238 239 240
                    left = false;
                    ui->leftAdvancedLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->rightAdvancedLayout->addWidget(box);
241
                }
242 243 244 245 246 247
            } else {
                delete tool;
            }
        }
    }

248 249 250 251 252
    //Load tabs for general configuration
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
        QWidget *tab = new QWidget(ui->tabWidget);
        ui->tabWidget->insertTab(2,tab,dir);
253
        tab->setLayout(new QVBoxLayout());
254
        tab->show();
255 256 257 258 259 260 261 262
        QScrollArea *area = new QScrollArea();
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget();
        scrollArea->setLayout(new QVBoxLayout());
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();
263 264 265 266 267 268 269 270 271 272 273 274 275
        QDir newdir = QDir(generaldir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", this);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
                    QGroupBox *box = new QGroupBox(this);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout());
                    box->layout()->addWidget(tool);
276
                    scrollArea->layout()->addWidget(box);
277 278 279 280 281 282 283 284 285 286 287 288
                } else {
                    delete tool;
                }
            }
        }
    }

    //Load tabs for vehicle specific configuration
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
        QWidget *tab = new QWidget(ui->tabWidget);
        ui->tabWidget->insertTab(2,tab,dir);
289
        tab->setLayout(new QVBoxLayout());
290
        tab->show();
291 292 293 294 295 296 297 298 299
        QScrollArea *area = new QScrollArea();
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget();
        scrollArea->setLayout(new QVBoxLayout());
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();

300 301 302 303 304 305 306 307 308 309
        QDir newdir = QDir(vehicledir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", this);
                tool->addUAS(mav);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
310
                    QGroupBox *box = new QGroupBox();
311 312 313
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout());
                    box->layout()->addWidget(tool);
314 315 316
                    scrollArea->layout()->addWidget(box);
                    box->show();
                    //gbox->layout()->addWidget(box);
317 318 319 320 321 322
                } else {
                    delete tool;
                }
            }
        }
    }
323 324


325
    // Load calibration
326
    //TODO: Handle this more gracefully, maybe have it scan the directory for multiple calibration entries?
327
    tool = new QGCToolWidget("", this);
328
    tool->addUAS(mav);
329
    if (tool->loadSettings(autopilotdir.absolutePath() + "/general/calibration/calibration.qgw", false))
330 331
    {
        toolWidgets.append(tool);
332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351
        QGroupBox *box = new QGroupBox(this);
        box->setTitle(tool->objectName());
        box->setLayout(new QVBoxLayout());
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
    } else {
        delete tool;
    }


    tool = new QGCToolWidget("", this);
    tool->addUAS(mav);
    if (tool->loadSettings(autopilotdir.absolutePath() + "/" +  mav->getSystemTypeName().toLower() + "/calibration/calibration.qgw", false))
    {
        toolWidgets.append(tool);
        QGroupBox *box = new QGroupBox(this);
        box->setTitle(tool->objectName());
        box->setLayout(new QVBoxLayout());
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
352 353
    } else {
        delete tool;
354
    }
355 356 357 358 359 360 361 362 363 364
    //description.txt
    QFile sensortipsfile(autopilotdir.absolutePath() + "/general/calibration/description.txt");
    sensortipsfile.open(QIODevice::ReadOnly);
    ui->sensorTips->setHtml(sensortipsfile.readAll());
    sensortipsfile.close();





365
}
366

367 368 369 370 371 372 373 374 375 376
void QGCVehicleConfig::loadConfig()
{
    QGCToolWidget* tool;

    QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower());
    QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets");
    QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets");
    if (!autopilotdir.exists("general"))
    {
     //TODO: Throw some kind of error here. There is no general configuration directory
377
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
378 379 380 381
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
382
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
383 384 385 386 387
    }
    qDebug() << autopilotdir.absolutePath();
    qDebug() << generaldir.absolutePath();
    qDebug() << vehicledir.absolutePath();
    QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
388
    if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
389
    {
390
        loadQgcConfig(false);
391
        doneLoadingConfig = true;
392 393
        return;
    }
394
    loadQgcConfig(true);
395 396 397

    QXmlStreamReader xml(xmlfile.readAll());
    xmlfile.close();
398 399

    //TODO: Testing to ensure that incorrectly formated XML won't break this.
400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420
    while (!xml.atEnd())
    {
        if (xml.isStartElement() && xml.name() == "paramfile")
        {
            xml.readNext();
            while ((xml.name() != "paramfile") && !xml.atEnd())
            {
                QString valuetype = "";
                if (xml.isStartElement() && (xml.name() == "vehicles" || xml.name() == "libraries")) //Enter into the vehicles loop
                {
                    valuetype = xml.name().toString();
                    xml.readNext();
                    while ((xml.name() != valuetype) && !xml.atEnd())
                    {
                        if (xml.isStartElement() && xml.name() == "parameters") //This is a parameter block
                        {
                            QString parametersname = "";
                            if (xml.attributes().hasAttribute("name"))
                            {
                                    parametersname = xml.attributes().value("name").toString();
                            }
421 422 423
                            QVariantMap genset;
                            QVariantMap advset;

424 425
                            QString setname = parametersname;
                            xml.readNext();
426 427
                            int genarraycount = 0;
                            int advarraycount = 0;
428 429 430 431 432 433
                            while ((xml.name() != "parameters") && !xml.atEnd())
                            {
                                if (xml.isStartElement() && xml.name() == "param")
                                {
                                    QString humanname = xml.attributes().value("humanName").toString();
                                    QString name = xml.attributes().value("name").toString();
434 435 436 437 438 439 440 441 442
                                    QString tab= xml.attributes().value("user").toString();
                                    if (tab == "Advanced")
                                    {
                                        advset["title"] = parametersname;
                                    }
                                    else
                                    {
                                        genset["title"] = parametersname;
                                    }
443 444 445 446 447 448 449 450 451 452 453 454 455 456 457
                                    if (name.contains(":"))
                                    {
                                        name = name.split(":")[1];
                                    }
                                    QString docs = xml.attributes().value("documentation").toString();
                                    paramTooltips[name] = name + " - " + docs;

                                    int type = -1; //Type of item
                                    QMap<QString,QString> fieldmap;
                                    xml.readNext();
                                    while ((xml.name() != "param") && !xml.atEnd())
                                    {
                                        if (xml.isStartElement() && xml.name() == "values")
                                        {
                                            type = 1; //1 is a combobox
458 459 460 461 462 463 464 465 466 467 468 469 470 471
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "COMBO";
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "COMBO";
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
                                            }
472 473 474 475 476 477 478 479 480
                                            int paramcount = 0;
                                            xml.readNext();
                                            while ((xml.name() != "values") && !xml.atEnd())
                                            {
                                                if (xml.isStartElement() && xml.name() == "value")
                                                {

                                                    QString code = xml.attributes().value("code").toString();
                                                    QString arg = xml.readElementText();
481 482 483 484 485 486 487 488 489 490
                                                    if (tab == "Advanced")
                                                    {
                                                        advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
                                                        advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
                                                    }
                                                    else
                                                    {
                                                        genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
                                                        genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
                                                    }
491 492 493 494
                                                    paramcount++;
                                                }
                                                xml.readNext();
                                            }
495 496 497 498 499 500 501 502
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
503 504 505 506 507 508 509 510 511 512 513 514
                                        }
                                        if (xml.isStartElement() && xml.name() == "field")
                                        {
                                            type = 2; //2 is a slider
                                            QString fieldtype = xml.attributes().value("name").toString();
                                            QString text = xml.readElementText();
                                            fieldmap[fieldtype] = text;
                                        }
                                        xml.readNext();
                                    }
                                    if (type == -1)
                                    {
515
                                        //Nothing inside! Assume it's a value, give it a default range.
516 517
                                        type = 2;
                                        QString fieldtype = "Range";
518
                                        QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
519 520 521 522
                                        fieldmap[fieldtype] = text;
                                    }
                                    if (type == 2)
                                    {
523 524 525 526 527 528 529 530 531 532 533 534 535 536
                                        if (tab == "Advanced")
                                        {
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "SLIDER";
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
                                        }
                                        else
                                        {
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "SLIDER";
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
                                        }
537 538 539 540
                                        if (fieldmap.contains("Range"))
                                        {
                                            float min = 0;
                                            float max = 0;
541
                                            //Some range fields list "0-10" and some list "0 10". Handle both.
542 543 544 545 546 547 548 549 550 551
                                            if (fieldmap["Range"].split(" ").size() > 1)
                                            {
                                                min = fieldmap["Range"].split(" ")[0].trimmed().toFloat();
                                                max = fieldmap["Range"].split(" ")[1].trimmed().toFloat();
                                            }
                                            else if (fieldmap["Range"].split("-").size() > 1)
                                            {
                                                min = fieldmap["Range"].split("-")[0].trimmed().toFloat();
                                                max = fieldmap["Range"].split("-")[1].trimmed().toFloat();
                                            }
552 553 554 555 556 557 558 559 560 561
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
                                            }
562 563
                                        }
                                    }
564 565 566 567 568 569 570 571 572 573
                                    if (tab == "Advanced")
                                    {
                                        advarraycount++;
                                        advset["count"] = advarraycount;
                                    }
                                    else
                                    {
                                        genarraycount++;
                                        genset["count"] = genarraycount;
                                    }
574 575 576
                                }
                                xml.readNext();
                            }
577
                            if (genarraycount > 0)
578
                            {
579 580 581 582 583 584 585
                                tool = new QGCToolWidget("", this);
                                tool->addUAS(mav);
                                tool->setTitle(parametersname);
                                tool->setObjectName(parametersname);
                                tool->setSettings(genset);
                                QList<QString> paramlist = tool->getParamList();
                                for (int i=0;i<paramlist.size();i++)
586
                                {
587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
                                        systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
                                        systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
                                        systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
                                    }
                                    else
                                    {
                                        libParamToWidgetMap->insert(paramlist[i],tool);
                                    }
604
                                }
605 606 607 608 609 610 611

                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(this);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout());
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
612
                                {
613
                                    ui->leftGeneralLayout->addWidget(box);
614
                                }
615
                                else if (valuetype == "libraries")
616
                                {
617
                                    ui->rightGeneralLayout->addWidget(box);
618
                                }
619 620 621 622 623 624 625 626 627 628 629 630
                                box->hide();
                                toolToBoxMap[tool] = box;
                            }
                            if (advarraycount > 0)
                            {
                                tool = new QGCToolWidget("", this);
                                tool->addUAS(mav);
                                tool->setTitle(parametersname);
                                tool->setObjectName(parametersname);
                                tool->setSettings(advset);
                                QList<QString> paramlist = tool->getParamList();
                                for (int i=0;i<paramlist.size();i++)
631
                                {
632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
                                        systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
                                        systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
                                        systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
                                    }
                                    else
                                    {
                                        libParamToWidgetMap->insert(paramlist[i],tool);
                                    }
649
                                }
650

651 652 653 654 655 656 657 658 659 660 661 662 663 664 665
                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(this);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout());
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
                                {
                                    ui->leftAdvancedLayout->addWidget(box);
                                }
                                else if (valuetype == "libraries")
                                {
                                    ui->rightAdvancedLayout->addWidget(box);
                                }
                                box->hide();
                                toolToBoxMap[tool] = box;
666
                            }
667 668


669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685


                        }
                        xml.readNext();
                    }

                }

                xml.readNext();
            }
        }
        xml.readNext();
    }
    if (mav)
    {
           mav->getParamManager()->setParamInfo(paramTooltips);
    }
686
    doneLoadingConfig = true;
687
    mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
688 689 690 691 692 693 694 695 696 697 698 699 700 701
}

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)));
702 703 704 705 706

        foreach (QGCToolWidget* tool, toolWidgets)
        {
            delete tool;
        }
707
        toolWidgets.clear();
708 709
    }

710 711 712
    // Reset current state
    resetCalibrationRC();

713 714
    chanCount = 0;

715 716
    // Connect new system
    mav = active;
717 718 719 720
    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)));
721

722
    if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
723
    {
724
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
725
    }
726
    else
727
    {
728
        //Indication that we have no meta data for this system type.
729
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
730 731
        systemTypeToParamMap[mav->getSystemTypeName()] = new QMap<QString,QGCToolWidget*>();
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
732 733
    }

734
    if (!paramTooltips.isEmpty())
735
    {
736
           mav->getParamManager()->setParamInfo(paramTooltips);
737 738
    }

739
   //    mav->requestParameters();
740 741 742

    QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/";
    qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
743

744 745 746 747

    //Load configuration after 1ms. This allows it to go into the event loop, and prevents application hangups due to the
    //amount of time it actually takes to load the configuration windows.
    QTimer::singleShot(1,this,SLOT(loadConfig()));
748 749

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
750 751 752 753 754
}
void QGCVehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
755 756
        rcMin[i] = 1200;
        rcMax[i] = 1800;
757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774
    }
}

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

775
    for (unsigned int i = 0; i < chanCount; ++i)
776
    {
777
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
Lorenz Meier's avatar
Lorenz Meier committed
778
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
779
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
780
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
781
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
782
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
783 784 785
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
786 787 788
    }

    // Write mappings
789 790 791 792
    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);
793
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
794
    QGC::SLEEP::usleep(50000);
795
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
796 797 798 799 800 801 802 803 804
    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);
805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820
}

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
821
        mav->requestParameter(0, minTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
822
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
823
        mav->requestParameter(0, trimTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
824
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
825
        mav->requestParameter(0, maxTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
826
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
827
        mav->requestParameter(0, revTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
828
        QGC::SLEEP::usleep(5000);
829 830 831 832 833 834 835
    }
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
836
    mav->writeParametersToStorage();
837 838 839 840
}

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

Bryant's avatar
Bryant committed
845
    if (chan + 1 > (int)chanCount) {
846 847 848 849 850 851 852 853 854 855 856 857 858 859
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
860 861
    }

862 863 864
    // Raw value
    rcValue[chan] = val;

865 866 867 868
    // Normalized value
    float normalized;

    if (val >= rcTrim[chan])
869
    {
870
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
871
    }
872 873 874 875 876 877 878 879 880
    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;
881

882 883 884
    if (chan == rcMapping[0])
    {
        // ROLL
885
        rcRoll = normalized;
886
    }
887
    if (chan == rcMapping[1])
888 889
    {
        // PITCH
890
        rcPitch = normalized;
891
    }
892
    if (chan == rcMapping[2])
893
    {
894
        rcYaw = normalized;
895
    }
896
    if (chan == rcMapping[3])
897 898
    {
        // THROTTLE
899 900 901 902
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
903
        }
904 905

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
906
    }
907
    if (chan == rcMapping[4])
908 909
    {
        // MODE SWITCH
910
        rcMode = normalized;
911
    }
912
    if (chan == rcMapping[5])
913 914
    {
        // AUX1
915
        rcAux1 = normalized;
916
    }
917
    if (chan == rcMapping[6])
918 919
    {
        // AUX2
920
        rcAux2 = normalized;
921
    }
922
    if (chan == rcMapping[7])
923 924
    {
        // AUX3
925
        rcAux3 = normalized;
926 927 928 929
    }

    changed = true;

930
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
931 932
}

933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965
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;
    }
}

966 967 968 969
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
970 971
    if (!doneLoadingConfig)
    {
972 973
        //We do not want to attempt to generate any UI elements until loading of the config file is complete.
        //We should re-request params later if needed, that is not implemented yet.
974 975
        return;
    }
976

977 978
    if (paramToWidgetMap->contains(parameterName))
    {
979
        //Main group of parameters of the selected airframe
980 981 982 983 984 985 986
        paramToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(paramToWidgetMap->value(parameterName)))
        {
            toolToBoxMap[paramToWidgetMap->value(parameterName)]->show();
        }
        else
        {
987
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
988 989 990
        }
    }
    else if (libParamToWidgetMap->contains(parameterName))
991
    {
992
        //All the library parameters
993 994
        libParamToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(libParamToWidgetMap->value(parameterName)))
995
        {
996
            toolToBoxMap[libParamToWidgetMap->value(parameterName)]->show();
997 998 999
        }
        else
        {
1000
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1001 1002 1003 1004
        }
    }
    else
    {
1005 1006
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
1007 1008 1009 1010 1011
        bool found = false;
        for (int i=0;i<toolWidgets.size();i++)
        {
            if (parameterName.startsWith(toolWidgets[i]->objectName()))
            {
1012
                //It should be grouped with this one, add it.
1013
                toolWidgets[i]->addParam(uas,component,parameterName,value);
1014
                libParamToWidgetMap->insert(parameterName,toolWidgets[i]);
1015 1016 1017 1018 1019 1020
                found  = true;
                break;
            }
        }
        if (!found)
        {
1021
            //New param type, create a QGroupBox for it.
1022 1023 1024 1025 1026 1027 1028 1029 1030 1031
            QGCToolWidget *tool = new QGCToolWidget("", this);
            QString tooltitle = parameterName;
            if (parameterName.split("_").size() > 1)
            {
                tooltitle = parameterName.split("_")[0] + "_";
            }
            tool->setTitle(tooltitle);
            tool->setObjectName(tooltitle);
            //tool->setSettings(set);
            tool->addParam(uas,component,parameterName,value);
1032
            libParamToWidgetMap->insert(parameterName,tool);
1033 1034 1035 1036 1037 1038
            toolWidgets.append(tool);
            QGroupBox *box = new QGroupBox(this);
            box->setTitle(tool->objectName());
            box->setLayout(new QVBoxLayout());
            box->layout()->addWidget(tool);

1039 1040 1041

            //Make sure we have similar number of widgets on each side.
            if (ui->leftAdvancedLayout->count() > ui->rightAdvancedLayout->count())
1042
            {
1043
                ui->rightAdvancedLayout->addWidget(box);
1044 1045 1046
            }
            else
            {
1047
                ui->leftAdvancedLayout->addWidget(box);
1048 1049 1050
            }
            toolToBoxMap[tool] = box;
        }
1051
    }
1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067

    // 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
1068
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1069
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
1070
        if (ok && (index >= 0) && (index < chanMax))
1071 1072 1073 1074 1075 1076 1077
        {
            rcMin[index] = value.toInt();
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1078
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1079
        if (ok && (index >= 0) && (index < chanMax))
1080 1081 1082 1083 1084 1085 1086
        {
            rcMax[index] = value.toInt();
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1087
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1088
        if (ok && (index >= 0) && (index < chanMax))
1089 1090 1091 1092 1093 1094 1095
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1096
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1097
        if (ok && (index >= 0) && (index < chanMax))
1098 1099
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
1100
            updateInvertedCheckboxes(index);
1101 1102 1103 1104 1105 1106 1107 1108
        }
    }

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

1109 1110 1111 1112 1113 1114 1115 1116
    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();
    }
1117 1118 1119 1120

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

    if (parameterName.contains("RC_MAP_ROLL")) {
1121 1122
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
1123 1124 1125
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
1126 1127
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
1128 1129 1130
    }

    if (parameterName.contains("RC_MAP_YAW")) {
1131 1132
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
1133 1134 1135
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
1136 1137
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
1138 1139 1140
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
1141 1142
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
1143 1144 1145
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
1146 1147
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
1148 1149 1150
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
1151
        rcMapping[6] = value.toInt() - 1;
1152
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
1153 1154 1155
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
1156
        rcMapping[7] = value.toInt() - 1;
1157
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
1158 1159 1160 1161 1162
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
1163
        rcScaling[0] = value.toFloat();
1164 1165 1166
    }

    if (parameterName.contains("RC_SCALE_PITCH")) {
1167
        rcScaling[1] = value.toFloat();
1168 1169 1170
    }

    if (parameterName.contains("RC_SCALE_YAW")) {
1171
        rcScaling[2] = value.toFloat();
1172 1173 1174
    }

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
1175
        rcScaling[3] = value.toFloat();
1176 1177 1178
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
1179
        rcScaling[4] = value.toFloat();
1180 1181 1182
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
1183
        rcScaling[5] = value.toFloat();
1184 1185 1186
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
1187
        rcScaling[6] = value.toFloat();
1188 1189 1190
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
1191
        rcScaling[7] = value.toFloat();
1192
    }
1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232
}

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)
    {
1233 1234
        if (rc_mode == RC_MODE_1)
        {
1235 1236 1237 1238
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
1239 1240 1241
        }
        else if (rc_mode == RC_MODE_2)
        {
1242 1243 1244 1245
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
1246 1247 1248
        }
        else if (rc_mode == RC_MODE_3)
        {
1249 1250 1251 1252
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
1253 1254 1255
        }
        else if (rc_mode == RC_MODE_4)
        {
1256 1257 1258 1259 1260 1261
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
        }

1262 1263 1264 1265
        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(' ')));
1266 1267

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

1270
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
1271
            ui->aux1Slider->setValue(rcAux1 * 50 + 50);
1272
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
1273 1274 1275 1276
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

1277
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
1278
            ui->aux2Slider->setValue(rcAux2 * 50 + 50);
1279
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
1280 1281 1282 1283
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

1284
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
1285
            ui->aux3Slider->setValue(rcAux3 * 50 + 50);
1286
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
1287 1288
        } else {
            ui->chanLabel_8->setText(tr("---"));
1289 1290
        }

1291 1292 1293
        changed = false;
    }
}