QGCVehicleConfig.cc 50.2 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
#include <QDir>
12
#include <QXmlStreamReader>
13

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

QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
    QWidget(parent),
22
    mav(NULL),
23
    chanCount(0),
24 25 26 27 28 29 30 31
    rcRoll(0.0f),
    rcPitch(0.0f),
    rcYaw(0.0f),
    rcThrottle(0.0f),
    rcMode(0.0f),
    rcAux1(0.0f),
    rcAux2(0.0f),
    rcAux3(0.0f),
32 33
    changed(true),
    rc_mode(RC_MODE_2),
34
    calibrationEnabled(false),
35 36
    ui(new Ui::QGCVehicleConfig)
{
37
    doneLoadingConfig = false;
38 39 40 41
    systemTypeToParamMap["FIXED_WING"] = new QMap<QString,QGCToolWidget*>();
    systemTypeToParamMap["QUADROTOR"] = new QMap<QString,QGCToolWidget*>();
    systemTypeToParamMap["GROUND_ROVER"] = new QMap<QString,QGCToolWidget*>();
    libParamToWidgetMap = new QMap<QString,QGCToolWidget*>();
42

43
    setObjectName("QGC_VEHICLECONFIG");
44
    ui->setupUi(this);
45 46 47 48

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

49 50
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

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

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

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

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

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

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

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

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

118 119 120
void QGCVehicleConfig::setTrimPositions()
{
    // Set trim for roll, pitch, yaw, throttle
121 122 123
    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
124 125 126 127 128 129 130 131 132 133
    // 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
    }
134 135 136 137
    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
138 139 140 141 142 143 144
}

void QGCVehicleConfig::detectChannelInversion()
{

}

145 146 147
void QGCVehicleConfig::startCalibrationRC()
{
    ui->rcTypeComboBox->setEnabled(false);
148
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
149
    resetCalibrationRC();
150
    calibrationEnabled = true;
151 152 153 154
}

void QGCVehicleConfig::stopCalibrationRC()
{
155
    calibrationEnabled = false;
156
    ui->rcTypeComboBox->setEnabled(true);
157
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
158
}
159 160

void QGCVehicleConfig::loadQgcConfig(bool primary)
161
{
162 163 164 165 166 167
    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
168
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
169 170 171 172
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
173
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
174
    }
175 176
    QGCToolWidget *tool;
    bool left = true;
177 178 179 180 181 182 183 184 185 186 187 188
    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);
189
                if (left)
190
                {
191 192 193 194 195 196 197
                    left = false;
                    ui->leftGeneralLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->rightGeneralLayout->addWidget(box);
198
                }
199 200 201 202 203
            } else {
                delete tool;
            }
        }
    }
204
    left = true;
205 206 207 208 209 210 211 212 213 214 215 216
    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);
217
                if (left)
218
                {
219 220 221 222 223 224 225
                    left = false;
                    ui->leftAdvancedLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->rightAdvancedLayout->addWidget(box);
226
                }
227 228 229 230 231 232
            } else {
                delete tool;
            }
        }
    }

233 234 235 236 237
    //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);
238
        tab->setLayout(new QVBoxLayout());
239
        tab->show();
240 241 242 243 244 245 246 247
        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();
248 249 250 251 252 253 254 255 256 257 258 259 260
        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);
261
                    scrollArea->layout()->addWidget(box);
262 263 264 265 266 267 268 269 270 271 272 273
                } 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);
274
        tab->setLayout(new QVBoxLayout());
275
        tab->show();
276 277 278 279 280 281 282 283 284
        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();

285 286 287 288 289 290 291 292 293 294
        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);
295
                    QGroupBox *box = new QGroupBox();
296 297 298
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout());
                    box->layout()->addWidget(tool);
299 300 301
                    scrollArea->layout()->addWidget(box);
                    box->show();
                    //gbox->layout()->addWidget(box);
302 303 304 305 306 307
                } else {
                    delete tool;
                }
            }
        }
    }
308 309


310
    // Load calibration
311
    //TODO: Handle this more gracefully, maybe have it scan the directory for multiple calibration entries?
312
    tool = new QGCToolWidget("", this);
313
    tool->addUAS(mav);
314
    if (tool->loadSettings(autopilotdir.absolutePath() + "/general/calibration/calibration.qgw", false))
315 316
    {
        toolWidgets.append(tool);
317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336
        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);
337 338
    } else {
        delete tool;
339
    }
340 341 342 343 344 345 346 347 348 349
    //description.txt
    QFile sensortipsfile(autopilotdir.absolutePath() + "/general/calibration/description.txt");
    sensortipsfile.open(QIODevice::ReadOnly);
    ui->sensorTips->setHtml(sensortipsfile.readAll());
    sensortipsfile.close();





350
}
351

352 353 354 355 356 357 358 359 360 361
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
362
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
363 364 365 366
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
367
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
368 369 370 371 372
    }
    qDebug() << autopilotdir.absolutePath();
    qDebug() << generaldir.absolutePath();
    qDebug() << vehicledir.absolutePath();
    QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
373
    if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
374
    {
375
        loadQgcConfig(false);
376
        doneLoadingConfig = true;
377 378
        return;
    }
379
    loadQgcConfig(true);
380 381 382

    QXmlStreamReader xml(xmlfile.readAll());
    xmlfile.close();
383 384

    //TODO: Testing to ensure that incorrectly formated XML won't break this.
385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405
    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();
                            }
406 407 408
                            QVariantMap genset;
                            QVariantMap advset;

409 410
                            QString setname = parametersname;
                            xml.readNext();
411 412
                            int genarraycount = 0;
                            int advarraycount = 0;
413 414 415 416 417 418
                            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();
419 420 421 422 423 424 425 426 427
                                    QString tab= xml.attributes().value("user").toString();
                                    if (tab == "Advanced")
                                    {
                                        advset["title"] = parametersname;
                                    }
                                    else
                                    {
                                        genset["title"] = parametersname;
                                    }
428 429 430 431 432 433 434 435 436 437 438 439 440 441 442
                                    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
443 444 445 446 447 448 449 450 451 452 453 454 455 456
                                            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;
                                            }
457 458 459 460 461 462 463 464 465
                                            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();
466 467 468 469 470 471 472 473 474 475
                                                    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();
                                                    }
476 477 478 479
                                                    paramcount++;
                                                }
                                                xml.readNext();
                                            }
480 481 482 483 484 485 486 487
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
488 489 490 491 492 493 494 495 496 497 498 499
                                        }
                                        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)
                                    {
500
                                        //Nothing inside! Assume it's a value, give it a default range.
501 502
                                        type = 2;
                                        QString fieldtype = "Range";
503
                                        QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
504 505 506 507
                                        fieldmap[fieldtype] = text;
                                    }
                                    if (type == 2)
                                    {
508 509 510 511 512 513 514 515 516 517 518 519 520 521
                                        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;
                                        }
522 523 524 525
                                        if (fieldmap.contains("Range"))
                                        {
                                            float min = 0;
                                            float max = 0;
526
                                            //Some range fields list "0-10" and some list "0 10". Handle both.
527 528 529 530 531 532 533 534 535 536
                                            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();
                                            }
537 538 539 540 541 542 543 544 545 546
                                            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;
                                            }
547 548
                                        }
                                    }
549 550 551 552 553 554 555 556 557 558
                                    if (tab == "Advanced")
                                    {
                                        advarraycount++;
                                        advset["count"] = advarraycount;
                                    }
                                    else
                                    {
                                        genarraycount++;
                                        genset["count"] = genarraycount;
                                    }
559 560 561
                                }
                                xml.readNext();
                            }
562
                            if (genarraycount > 0)
563
                            {
564 565 566 567 568 569 570
                                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++)
571
                                {
572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588
                                    //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);
                                    }
589
                                }
590 591 592 593 594 595 596

                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(this);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout());
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
597
                                {
598
                                    ui->leftGeneralLayout->addWidget(box);
599
                                }
600
                                else if (valuetype == "libraries")
601
                                {
602
                                    ui->rightGeneralLayout->addWidget(box);
603
                                }
604 605 606 607 608 609 610 611 612 613 614 615
                                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++)
616
                                {
617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633
                                    //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);
                                    }
634
                                }
635

636 637 638 639 640 641 642 643 644 645 646 647 648 649 650
                                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;
651
                            }
652 653


654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670


                        }
                        xml.readNext();
                    }

                }

                xml.readNext();
            }
        }
        xml.readNext();
    }
    if (mav)
    {
           mav->getParamManager()->setParamInfo(paramTooltips);
    }
671
    doneLoadingConfig = true;
672
    mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
673 674
}

675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706
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)));

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

    // Reset current state
    resetCalibrationRC();

    chanCount = 0;

    // Connect new system
    mav = active;
    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)));

707 708 709 710 711 712
    if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
    {
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }
    else
    {
713
        //Indication that we have no meta data for this system type.
714 715 716
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
    }

717 718 719 720 721
    if (!paramTooltips.isEmpty())
    {
           mav->getParamManager()->setParamInfo(paramTooltips);
    }

722
   //    mav->requestParameters();
723 724 725 726 727 728 729 730 731 732 733

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


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

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
}
734 735 736 737
void QGCVehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
738 739
        rcMin[i] = 1200;
        rcMax[i] = 1800;
740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757
    }
}

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

758
    for (unsigned int i = 0; i < chanCount; ++i)
759
    {
760
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
Lorenz Meier's avatar
Lorenz Meier committed
761
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
762
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
763
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
764
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
765
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
766 767 768
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
769 770 771
    }

    // Write mappings
772 773 774 775
    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);
776
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
777
    QGC::SLEEP::usleep(50000);
778
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
779 780 781 782 783 784 785 786 787
    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);
788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803
}

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
804
        mav->requestParameter(0, minTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
805
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
806
        mav->requestParameter(0, trimTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
807
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
808
        mav->requestParameter(0, maxTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
809
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
810
        mav->requestParameter(0, revTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
811
        QGC::SLEEP::usleep(5000);
812 813 814 815 816 817 818
    }
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
819
    mav->writeParametersToStorage();
820 821 822 823
}

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

Bryant's avatar
Bryant committed
828
    if (chan + 1 > (int)chanCount) {
829 830 831 832 833 834 835 836 837 838 839 840 841 842
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
843 844
    }

845 846 847
    // Raw value
    rcValue[chan] = val;

848 849 850 851
    // Normalized value
    float normalized;

    if (val >= rcTrim[chan])
852
    {
853
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
854
    }
855 856 857 858 859 860 861 862 863
    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;
864

865 866 867
    if (chan == rcMapping[0])
    {
        // ROLL
868
        rcRoll = normalized;
869
    }
870
    if (chan == rcMapping[1])
871 872
    {
        // PITCH
873
        rcPitch = normalized;
874
    }
875
    if (chan == rcMapping[2])
876
    {
877
        rcYaw = normalized;
878
    }
879
    if (chan == rcMapping[3])
880 881
    {
        // THROTTLE
882 883 884 885
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
886
        }
887 888

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
889
    }
890
    if (chan == rcMapping[4])
891 892
    {
        // MODE SWITCH
893
        rcMode = normalized;
894
    }
895
    if (chan == rcMapping[5])
896 897
    {
        // AUX1
898
        rcAux1 = normalized;
899
    }
900
    if (chan == rcMapping[6])
901 902
    {
        // AUX2
903
        rcAux2 = normalized;
904
    }
905
    if (chan == rcMapping[7])
906 907
    {
        // AUX3
908
        rcAux3 = normalized;
909 910 911 912
    }

    changed = true;

913
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
914 915
}

916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948
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;
    }
}

949 950 951 952
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
953 954
    if (!doneLoadingConfig)
    {
955 956
        //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.
957 958
        return;
    }
959

960 961
    if (paramToWidgetMap->contains(parameterName))
    {
962
        //Main group of parameters of the selected airframe
963 964 965 966 967 968 969
        paramToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(paramToWidgetMap->value(parameterName)))
        {
            toolToBoxMap[paramToWidgetMap->value(parameterName)]->show();
        }
        else
        {
970
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
971 972 973
        }
    }
    else if (libParamToWidgetMap->contains(parameterName))
974
    {
975
        //All the library parameters
976 977
        libParamToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(libParamToWidgetMap->value(parameterName)))
978
        {
979
            toolToBoxMap[libParamToWidgetMap->value(parameterName)]->show();
980 981 982
        }
        else
        {
983
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
984 985 986 987
        }
    }
    else
    {
988 989
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
990 991 992 993 994
        bool found = false;
        for (int i=0;i<toolWidgets.size();i++)
        {
            if (parameterName.startsWith(toolWidgets[i]->objectName()))
            {
995
                //It should be grouped with this one, add it.
996
                toolWidgets[i]->addParam(uas,component,parameterName,value);
997
                libParamToWidgetMap->insert(parameterName,toolWidgets[i]);
998 999 1000 1001 1002 1003
                found  = true;
                break;
            }
        }
        if (!found)
        {
1004
            //New param type, create a QGroupBox for it.
1005 1006 1007 1008 1009 1010 1011 1012 1013 1014
            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);
1015
            libParamToWidgetMap->insert(parameterName,tool);
1016 1017 1018 1019 1020 1021
            toolWidgets.append(tool);
            QGroupBox *box = new QGroupBox(this);
            box->setTitle(tool->objectName());
            box->setLayout(new QVBoxLayout());
            box->layout()->addWidget(tool);

1022 1023 1024

            //Make sure we have similar number of widgets on each side.
            if (ui->leftAdvancedLayout->count() > ui->rightAdvancedLayout->count())
1025
            {
1026
                ui->rightAdvancedLayout->addWidget(box);
1027 1028 1029
            }
            else
            {
1030
                ui->leftAdvancedLayout->addWidget(box);
1031 1032 1033
            }
            toolToBoxMap[tool] = box;
        }
1034 1035
    }

1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050
    // 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
1051
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1052
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
1053
        if (ok && (index >= 0) && (index < chanMax))
1054 1055 1056 1057 1058 1059 1060
        {
            rcMin[index] = value.toInt();
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1061
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1062
        if (ok && (index >= 0) && (index < chanMax))
1063 1064 1065 1066 1067 1068 1069
        {
            rcMax[index] = value.toInt();
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1070
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1071
        if (ok && (index >= 0) && (index < chanMax))
1072 1073 1074 1075 1076 1077 1078
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1079
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1080
        if (ok && (index >= 0) && (index < chanMax))
1081 1082
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
1083
            updateInvertedCheckboxes(index);
1084 1085 1086 1087 1088 1089 1090 1091
        }
    }

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

1092 1093 1094 1095 1096 1097 1098 1099
    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();
    }
1100 1101 1102 1103

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

    if (parameterName.contains("RC_MAP_ROLL")) {
1104 1105
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
1106 1107 1108
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
1109 1110
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
1111 1112 1113
    }

    if (parameterName.contains("RC_MAP_YAW")) {
1114 1115
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
1116 1117 1118
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
1119 1120
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
1121 1122 1123
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
1124 1125
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
1126 1127 1128
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
1129 1130
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
1131 1132 1133
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
1134
        rcMapping[6] = value.toInt() - 1;
1135
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
1136 1137 1138
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
1139
        rcMapping[7] = value.toInt() - 1;
1140
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
1141 1142 1143 1144 1145
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
1146
        rcScaling[0] = value.toFloat();
1147 1148 1149
    }

    if (parameterName.contains("RC_SCALE_PITCH")) {
1150
        rcScaling[1] = value.toFloat();
1151 1152 1153
    }

    if (parameterName.contains("RC_SCALE_YAW")) {
1154
        rcScaling[2] = value.toFloat();
1155 1156 1157
    }

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
1158
        rcScaling[3] = value.toFloat();
1159 1160 1161
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
1162
        rcScaling[4] = value.toFloat();
1163 1164 1165
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
1166
        rcScaling[5] = value.toFloat();
1167 1168 1169
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
1170
        rcScaling[6] = value.toFloat();
1171 1172 1173
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
1174
        rcScaling[7] = value.toFloat();
1175
    }
1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215
}

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)
    {
1216 1217
        if (rc_mode == RC_MODE_1)
        {
1218 1219 1220 1221
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
1222 1223 1224
        }
        else if (rc_mode == RC_MODE_2)
        {
1225 1226 1227 1228
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
1229 1230 1231
        }
        else if (rc_mode == RC_MODE_3)
        {
1232 1233 1234 1235
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
1236 1237 1238
        }
        else if (rc_mode == RC_MODE_4)
        {
1239 1240 1241 1242 1243 1244
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
        }

1245 1246 1247 1248
        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(' ')));
1249 1250

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

1253
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
1254
            ui->aux1Slider->setValue(rcAux1 * 50 + 50);
1255
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
1256 1257 1258 1259
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

1260
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
1261
            ui->aux2Slider->setValue(rcAux2 * 50 + 50);
1262
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
1263 1264 1265 1266
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

1267
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
1268
            ui->aux3Slider->setValue(rcAux3 * 50 + 50);
1269
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
1270 1271
        } else {
            ui->chanLabel_8->setText(tr("---"));
1272 1273
        }

1274 1275 1276
        changed = false;
    }
}