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

15
#include "QGCVehicleConfig.h"
16

17
#include "QGC.h"
18
#include "QGCToolWidget.h"
19 20
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
21 22 23 24
#include "ui_QGCVehicleConfig.h"

QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
    QWidget(parent),
25
    mav(NULL),
26
    chanCount(0),
27 28 29 30 31 32 33 34
    rcRoll(0.0f),
    rcPitch(0.0f),
    rcYaw(0.0f),
    rcThrottle(0.0f),
    rcMode(0.0f),
    rcAux1(0.0f),
    rcAux2(0.0f),
    rcAux3(0.0f),
35
    changed(true),
36
    rc_mode(RC_MODE_NONE),
37
    calibrationEnabled(false),
38 39
    ui(new Ui::QGCVehicleConfig)
{
40
    doneLoadingConfig = false;
41

42
    setObjectName("QGC_VEHICLECONFIG");
43
    ui->setupUi(this);
44

45 46 47 48
    ui->rollWidget->setOrientation(Qt::Horizontal);
    ui->rollWidget->setName("Roll");
    ui->yawWidget->setOrientation(Qt::Horizontal);
    ui->yawWidget->setName("Yaw");
49 50
    ui->pitchWidget->setName("Pitch");
    ui->throttleWidget->setName("Throttle");
51 52 53 54 55 56 57 58 59
    ui->radio5Widget->setOrientation(Qt::Horizontal);
    ui->radio5Widget->setName("Radio 5");
    ui->radio6Widget->setOrientation(Qt::Horizontal);
    ui->radio6Widget->setName("Radio 6");
    ui->radio7Widget->setOrientation(Qt::Horizontal);
    ui->radio7Widget->setName("Radio 7");
    ui->radio8Widget->setOrientation(Qt::Horizontal);
    ui->radio8Widget->setName("Radio 8");

60 61 62 63 64
    connect(ui->rcMenuButton,SIGNAL(clicked()),this,SLOT(rcMenuButtonClicked()));
    connect(ui->sensorMenuButton,SIGNAL(clicked()),this,SLOT(sensorMenuButtonClicked()));
    connect(ui->generalMenuButton,SIGNAL(clicked()),this,SLOT(generalMenuButtonClicked()));
    connect(ui->advancedMenuButton,SIGNAL(clicked()),this,SLOT(advancedMenuButtonClicked()));

65 66
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

67
    ui->rcCalibrationButton->setCheckable(true);
68
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
69
    connect(ui->setButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
70
    connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
71
    //connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));
72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91

    /* 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)));
92 93 94 95 96

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

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

97
    for (unsigned int i = 0; i < chanMax; i++)
98
    {
99
        rcValue[i] = UINT16_MAX;
100
        rcMapping[i] = i;
101 102 103 104 105
    }

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
106 107 108

    ui->advancedGroupBox->hide();
    connect(ui->advancedCheckBox,SIGNAL(toggled(bool)),ui->advancedGroupBox,SLOT(setShown(bool)));
109
}
110 111 112 113 114 115 116 117 118 119
void QGCVehicleConfig::rcMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(0);
}

void QGCVehicleConfig::sensorMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(1);
}

120 121 122 123 124
void QGCVehicleConfig::generalMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-2);
}

125 126 127 128
void QGCVehicleConfig::advancedMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-1);
}
129 130 131 132 133

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

135 136
void QGCVehicleConfig::setRCModeIndex(int newRcMode)
{
137
    if (newRcMode > 0 && newRcMode < 6)
138
    {
139
        //rc_mode = (enum RC_MODE) (newRcMode+1);
140 141 142
        changed = true;
    }
}
143 144 145 146 147 148 149 150 151 152 153 154 155

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

156 157
void QGCVehicleConfig::setTrimPositions()
{
Lorenz Meier's avatar
Lorenz Meier committed
158 159 160 161 162 163
    // 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
164
    else if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100)
Lorenz Meier's avatar
Lorenz Meier committed
165 166 167
    {
        rcTrim[rcMapping[3]] = rcMax[rcMapping[3]];   // throttle
    }
168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184
    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

185 186 187 188
    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
189 190 191 192 193 194 195
}

void QGCVehicleConfig::detectChannelInversion()
{

}

196 197
void QGCVehicleConfig::startCalibrationRC()
{
198 199
    QMessageBox::information(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and reciever are powered and connected\n\nClick OK to confirm");
    QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
200
    ui->rcTypeComboBox->setEnabled(false);
201
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
202
    resetCalibrationRC();
203
    calibrationEnabled = true;
204 205 206 207 208 209 210 211
    ui->rollWidget->showMinMax();
    ui->pitchWidget->showMinMax();
    ui->yawWidget->showMinMax();
    ui->throttleWidget->showMinMax();
    ui->radio5Widget->showMinMax();
    ui->radio6Widget->showMinMax();
    ui->radio7Widget->showMinMax();
    ui->radio8Widget->showMinMax();
212 213 214 215
}

void QGCVehicleConfig::stopCalibrationRC()
{
216
    QMessageBox::information(0,"Trims","Ensure all sticks are centeres and throttle is in the downmost position, click OK to continue");
217
    calibrationEnabled = false;
218
    ui->rcTypeComboBox->setEnabled(true);
219
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237
    ui->rollWidget->hideMinMax();
    ui->pitchWidget->hideMinMax();
    ui->yawWidget->hideMinMax();
    ui->throttleWidget->hideMinMax();
    ui->radio5Widget->hideMinMax();
    ui->radio6Widget->hideMinMax();
    ui->radio7Widget->hideMinMax();
    ui->radio8Widget->hideMinMax();
    QString statusstr;
    statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n";
    statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500\n\n";
    statusstr += "Channel\tMin\tCenter\tMax\n";
    statusstr += "--------------------\n";
    for (int i=0;i<8;i++)
    {
        statusstr += QString::number(i) + "\t" + QString::number(rcMin[i]) + "\t" + QString::number(rcValue[i]) + "\t" + QString::number(rcMax[i]) + "\n";
    }
    QMessageBox::information(0,"Status",statusstr);
238 239
}

240
void QGCVehicleConfig::loadQgcConfig(bool primary)
241
{
242
    Q_UNUSED(primary);
243 244 245 246 247 248
    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
249
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
250 251 252 253
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
254
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
255
    }
256 257

    // Generate widgets for the General tab.
258 259
    QGCToolWidget *tool;
    bool left = true;
260 261 262
    foreach (QString file,generaldir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
263 264
            QWidget* parent = left?ui->generalLeftContents:ui->generalRightContents;
            tool = new QGCToolWidget("", parent);
265 266 267
            if (tool->loadSettings(generaldir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
268
                QGroupBox *box = new QGroupBox(parent);
269
                box->setTitle(tool->objectName());
270
                box->setLayout(new QVBoxLayout(box));
271
                box->layout()->addWidget(tool);
272
                if (left)
273
                {
274
                    left = false;
275
                    ui->generalLeftLayout->addWidget(box);
276 277 278 279
                }
                else
                {
                    left = true;
280
                    ui->generalRightLayout->addWidget(box);
281
                }
282 283 284 285 286
            } else {
                delete tool;
            }
        }
    }
287 288

    // Generate widgets for the Advanced tab.
289
    left = true;
290 291 292
    foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
293 294
            QWidget* parent = left?ui->advancedLeftContents:ui->advancedRightContents;
            tool = new QGCToolWidget("", parent);
295 296 297
            if (tool->loadSettings(vehicledir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
298
                QGroupBox *box = new QGroupBox(parent);
299
                box->setTitle(tool->objectName());
300
                box->setLayout(new QVBoxLayout(box));
301
                box->layout()->addWidget(tool);
302
                if (left)
303
                {
304
                    left = false;
305
                    ui->advancedLeftLayout->addWidget(box);
306 307 308 309
                }
                else
                {
                    left = true;
310
                    ui->advancedRightLayout->addWidget(box);
311
                }
312 313 314 315 316 317
            } else {
                delete tool;
            }
        }
    }

318
    // Load tabs for general configuration
319 320
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
321 322 323
        QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3);
        connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
        ui->navBarLayout->insertWidget(2,button);
324
        button->setMinimumHeight(75);
325 326 327 328 329 330
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
        QWidget *tab = new QWidget(ui->stackedWidget);
        ui->stackedWidget->insertWidget(2,tab);
        buttonToWidgetMap[button] = tab;
331
        tab->setLayout(new QVBoxLayout());
332
        tab->show();
333
        QScrollArea *area = new QScrollArea(tab);
334
        tab->layout()->addWidget(area);
335 336
        QWidget *scrollArea = new QWidget(tab);
        scrollArea->setLayout(new QVBoxLayout(tab));
337 338 339 340
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();
341 342 343 344
        QDir newdir = QDir(generaldir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
345
                tool = new QGCToolWidget("", tab);
346 347 348 349
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
350
                    QGroupBox *box = new QGroupBox(tab);
351
                    box->setTitle(tool->objectName());
352
                    box->setLayout(new QVBoxLayout(tab));
353
                    box->layout()->addWidget(tool);
354
                    scrollArea->layout()->addWidget(box);
355 356 357 358 359 360 361
                } else {
                    delete tool;
                }
            }
        }
    }

362
    // Load additional tabs for vehicle specific configuration
363 364
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
365 366 367 368 369 370 371 372
        QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3);
        connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
        ui->navBarLayout->insertWidget(2,button);

        QWidget *tab = new QWidget(ui->stackedWidget);
        ui->stackedWidget->insertWidget(2,tab);
        buttonToWidgetMap[button] = tab;

373
        button->setMinimumHeight(75);
374 375 376
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
377
        tab->setLayout(new QVBoxLayout());
378
        tab->show();
379
        QScrollArea *area = new QScrollArea(tab);
380
        tab->layout()->addWidget(area);
381 382
        QWidget *scrollArea = new QWidget(tab);
        scrollArea->setLayout(new QVBoxLayout(tab));
383 384 385 386 387
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();

388 389 390 391
        QDir newdir = QDir(vehicledir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
392
                tool = new QGCToolWidget("", tab);
393 394 395 396 397
                tool->addUAS(mav);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
398
                    QGroupBox *box = new QGroupBox(tab);
399
                    box->setTitle(tool->objectName());
400
                    box->setLayout(new QVBoxLayout(box));
401
                    box->layout()->addWidget(tool);
402 403 404
                    scrollArea->layout()->addWidget(box);
                    box->show();
                    //gbox->layout()->addWidget(box);
405 406 407 408 409 410
                } else {
                    delete tool;
                }
            }
        }
    }
411

412
    // Load general calibration for autopilot
413
    //TODO: Handle this more gracefully, maybe have it scan the directory for multiple calibration entries?
414
    tool = new QGCToolWidget("", ui->sensorContents);
415
    tool->addUAS(mav);
416
    if (tool->loadSettings(autopilotdir.absolutePath() + "/general/calibration/calibration.qgw", false))
417 418
    {
        toolWidgets.append(tool);
419
        QGroupBox *box = new QGroupBox(ui->sensorContents);
420
        box->setTitle(tool->objectName());
421
        box->setLayout(new QVBoxLayout(box));
422 423 424 425 426 427
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
    } else {
        delete tool;
    }

428 429
    // Load vehicle-specific autopilot configuration
    tool = new QGCToolWidget("", ui->sensorContents);
430 431 432 433
    tool->addUAS(mav);
    if (tool->loadSettings(autopilotdir.absolutePath() + "/" +  mav->getSystemTypeName().toLower() + "/calibration/calibration.qgw", false))
    {
        toolWidgets.append(tool);
434
        QGroupBox *box = new QGroupBox(ui->sensorContents);
435
        box->setTitle(tool->objectName());
436
        box->setLayout(new QVBoxLayout(box));
437 438
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
439 440
    } else {
        delete tool;
441
    }
442

443 444 445 446 447
    //description.txt
    QFile sensortipsfile(autopilotdir.absolutePath() + "/general/calibration/description.txt");
    sensortipsfile.open(QIODevice::ReadOnly);
    ui->sensorTips->setHtml(sensortipsfile.readAll());
    sensortipsfile.close();
448
}
449 450 451 452 453 454 455 456 457 458 459 460 461
void QGCVehicleConfig::menuButtonClicked()
{
    QPushButton *button = qobject_cast<QPushButton*>(sender());
    if (!button)
    {
        return;
    }
    if (buttonToWidgetMap.contains(button))
    {
        ui->stackedWidget->setCurrentWidget(buttonToWidgetMap[button]);
    }

}
462

463 464 465 466 467 468 469 470 471 472
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
473
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
474 475 476 477
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
478
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
479 480 481 482 483
    }
    qDebug() << autopilotdir.absolutePath();
    qDebug() << generaldir.absolutePath();
    qDebug() << vehicledir.absolutePath();
    QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
484
    if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
485
    {
486
        loadQgcConfig(false);
487
        doneLoadingConfig = true;
488 489
        return;
    }
490
    loadQgcConfig(true);
491 492 493

    QXmlStreamReader xml(xmlfile.readAll());
    xmlfile.close();
494

495
    //TODO: Testing to ensure that incorrectly formatted XML won't break this.
496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516
    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();
                            }
517 518 519
                            QVariantMap genset;
                            QVariantMap advset;

520 521
                            QString setname = parametersname;
                            xml.readNext();
522 523
                            int genarraycount = 0;
                            int advarraycount = 0;
524 525 526 527 528 529
                            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();
530 531 532 533 534 535 536 537 538
                                    QString tab= xml.attributes().value("user").toString();
                                    if (tab == "Advanced")
                                    {
                                        advset["title"] = parametersname;
                                    }
                                    else
                                    {
                                        genset["title"] = parametersname;
                                    }
539 540 541 542 543 544 545 546 547 548 549 550 551 552 553
                                    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
554 555 556 557 558 559 560 561 562 563 564 565 566 567
                                            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;
                                            }
568 569 570 571 572 573 574 575 576
                                            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();
577 578 579 580 581 582 583 584 585 586
                                                    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();
                                                    }
587 588 589 590
                                                    paramcount++;
                                                }
                                                xml.readNext();
                                            }
591 592 593 594 595 596 597 598
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
599 600 601 602 603 604 605 606 607 608 609 610
                                        }
                                        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)
                                    {
611
                                        //Nothing inside! Assume it's a value, give it a default range.
612 613
                                        type = 2;
                                        QString fieldtype = "Range";
614
                                        QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
615 616 617 618
                                        fieldmap[fieldtype] = text;
                                    }
                                    if (type == 2)
                                    {
619 620 621 622 623 624 625 626 627 628 629 630 631 632
                                        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;
                                        }
633 634 635 636
                                        if (fieldmap.contains("Range"))
                                        {
                                            float min = 0;
                                            float max = 0;
637
                                            //Some range fields list "0-10" and some list "0 10". Handle both.
638 639 640 641 642 643 644 645 646 647
                                            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();
                                            }
648 649 650 651 652 653 654 655 656 657
                                            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;
                                            }
658 659
                                        }
                                    }
660 661 662 663 664 665 666 667 668 669
                                    if (tab == "Advanced")
                                    {
                                        advarraycount++;
                                        advset["count"] = advarraycount;
                                    }
                                    else
                                    {
                                        genarraycount++;
                                        genset["count"] = genarraycount;
                                    }
670 671 672
                                }
                                xml.readNext();
                            }
673
                            if (genarraycount > 0)
674
                            {
675 676 677 678 679 680 681 682 683 684
                                QWidget* parent = this;
                                if (valuetype == "vehicles")
                                {
                                    parent = ui->generalLeftContents;
                                }
                                else if (valuetype == "libraries")
                                {
                                    parent = ui->generalRightContents;
                                }
                                tool = new QGCToolWidget("", parent);
685 686 687 688 689 690
                                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++)
691
                                {
692 693 694
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
695
                                        systemTypeToParamMap["FIXED_WING"].insert(paramlist[i],tool);
696 697 698
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
699
                                        systemTypeToParamMap["QUADROTOR"].insert(paramlist[i],tool);
700 701 702
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
703
                                        systemTypeToParamMap["GROUND_ROVER"].insert(paramlist[i],tool);
704 705 706
                                    }
                                    else
                                    {
707
                                        libParamToWidgetMap.insert(paramlist[i],tool);
708
                                    }
709
                                }
710 711

                                toolWidgets.append(tool);
712
                                QGroupBox *box = new QGroupBox(parent);
713
                                box->setTitle(tool->objectName());
714
                                box->setLayout(new QVBoxLayout(box));
715 716
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
717
                                {
718
                                    ui->generalLeftLayout->addWidget(box);
719
                                }
720
                                else if (valuetype == "libraries")
721
                                {
722
                                    ui->generalRightLayout->addWidget(box);
723
                                }
724 725 726 727 728
                                box->hide();
                                toolToBoxMap[tool] = box;
                            }
                            if (advarraycount > 0)
                            {
729 730 731 732 733 734 735 736 737 738
                                QWidget* parent = this;
                                if (valuetype == "vehicles")
                                {
                                    parent = ui->generalLeftContents;
                                }
                                else if (valuetype == "libraries")
                                {
                                    parent = ui->generalRightContents;
                                }
                                tool = new QGCToolWidget("", parent);
739 740 741 742 743 744
                                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++)
745
                                {
746 747 748
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
749
                                        systemTypeToParamMap["FIXED_WING"].insert(paramlist[i],tool);
750 751 752
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
753
                                        systemTypeToParamMap["QUADROTOR"].insert(paramlist[i],tool);
754 755 756
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
757
                                        systemTypeToParamMap["GROUND_ROVER"].insert(paramlist[i],tool);
758 759 760
                                    }
                                    else
                                    {
761
                                        libParamToWidgetMap.insert(paramlist[i],tool);
762
                                    }
763
                                }
764

765
                                toolWidgets.append(tool);
766
                                QGroupBox *box = new QGroupBox(parent);
767
                                box->setTitle(tool->objectName());
768
                                box->setLayout(new QVBoxLayout(box));
769 770 771
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
                                {
772
                                    ui->generalLeftLayout->addWidget(box);
773 774 775
                                }
                                else if (valuetype == "libraries")
                                {
776
                                    ui->generalRightLayout->addWidget(box);
777 778 779
                                }
                                box->hide();
                                toolToBoxMap[tool] = box;
780 781 782 783 784 785 786 787 788 789
                            }
                        }
                        xml.readNext();
                    }
                }
                xml.readNext();
            }
        }
        xml.readNext();
    }
790

791 792 793
    if (!paramTooltips.isEmpty()) {
           paramMgr->setParamDescriptions(paramTooltips);
    }
794
    doneLoadingConfig = true;
795
    //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
796
    paramMgr->requestParameterListIfEmpty();
797 798 799 800
}

void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
Lorenz Meier's avatar
Lorenz Meier committed
801 802 803 804 805 806 807 808 809 810 811 812 813 814 815
    // Hide items if NULL and abort
    if (!active) {
        ui->setButton->setEnabled(false);
        ui->refreshButton->setEnabled(false);
        ui->readButton->show();
        ui->readButton->setEnabled(false);
        ui->writeButton->show();
        ui->writeButton->setEnabled(false);
        ui->loadFileButton->setEnabled(false);
        ui->saveFileButton->setEnabled(false);

        return;
    }


816
    // Do nothing if system is the same
817
    if (mav == active) return;
818 819 820 821 822 823 824 825

    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)));
Lorenz Meier's avatar
Lorenz Meier committed
826
        disconnect(ui->refreshButton,SIGNAL(clicked()),mav,SLOT(requestParameters()));
827

828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851
        // Delete all children from all fixed tabs.
        foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>())
        {
            child->deleteLater();
        }
        foreach(QWidget* child, ui->generalRightContents->findChildren<QWidget*>())
        {
            child->deleteLater();
        }
        foreach(QWidget* child, ui->advancedLeftContents->findChildren<QWidget*>())
        {
            child->deleteLater();
        }
        foreach(QWidget* child, ui->advancedRightContents->findChildren<QWidget*>())
        {
            child->deleteLater();
        }
        foreach(QWidget* child, ui->sensorContents->findChildren<QWidget*>())
        {
            child->deleteLater();
        }

        // And then delete any custom tabs
        foreach(QWidget* child, additionalTabs)
852
        {
853
            child->deleteLater();
854
        }
855 856
        additionalTabs.clear();

857
        toolWidgets.clear();
858
        paramToWidgetMap.clear();
859 860 861 862
        libParamToWidgetMap.clear();
        systemTypeToParamMap.clear();
        toolToBoxMap.clear();
        paramTooltips.clear();
863 864
    }

Lorenz Meier's avatar
Lorenz Meier committed
865 866
    // Connect new system
    mav = active;
867
    paramMgr = mav->getParamManager();
Lorenz Meier's avatar
Lorenz Meier committed
868

869 870 871
    // Reset current state
    resetCalibrationRC();

Lorenz Meier's avatar
Lorenz Meier committed
872 873 874
    requestCalibrationRC();
    mav->requestParameter(0, "RC_TYPE");

875 876
    chanCount = 0;

877
    // Connect new system
878 879 880 881
    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)));
Lorenz Meier's avatar
Lorenz Meier committed
882
    connect(ui->refreshButton, SIGNAL(clicked()), active, SLOT(requestParameters()));
883

884
    if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
885
    {
886
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
887
    }
888
    else
889
    {
890
        //Indication that we have no meta data for this system type.
891
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
892
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
893 894
    }

895
    if (!paramTooltips.isEmpty())
896
    {
897
           mav->getParamManager()->setParamDescriptions(paramTooltips);
898 899
    }

900
    qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
901

902 903 904
    //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()));
905 906

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
907 908 909 910 911 912 913 914

    // Since a system is now connected, enable the VehicleConfig UI.
    ui->setButton->setEnabled(true);
    ui->refreshButton->setEnabled(true);
    ui->readButton->setEnabled(true);
    ui->writeButton->setEnabled(true);
    ui->loadFileButton->setEnabled(true);
    ui->saveFileButton->setEnabled(true);
915 916 917 918 919
    if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA")
    {
        ui->readButton->hide();
        ui->writeButton->hide();
    }
920
}
921

922 923 924 925
void QGCVehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
926 927
        rcMin[i] = 1500;
        rcMax[i] = 1500;
928 929 930 931 932 933 934 935 936 937
    }
}

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

938 939
    setTrimPositions();

940 941 942 943 944 945 946 947
    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

948
    //TODO consolidate RC param sending in the UAS comms mgr
949
    for (unsigned int i = 0; i < chanCount; ++i)
950
    {
951
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
Lorenz Meier's avatar
Lorenz Meier committed
952
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
953
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
954
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
955
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
956
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
957 958 959
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
960 961 962
    }

    // Write mappings
963 964 965 966
    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);
967
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
968
    QGC::SLEEP::usleep(50000);
969
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
970 971 972 973 974 975 976 977 978
    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);
979 980 981 982
}

void QGCVehicleConfig::requestCalibrationRC()
{
983
    paramMgr->requestRcCalibrationParamsUpdate();
984 985 986 987 988 989
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
990

991
    mav->writeParametersToStorage();
992 993 994 995
}

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

Bryant's avatar
Bryant committed
1000
    if (chan + 1 > (int)chanCount) {
1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
1015 1016
    }

1017 1018 1019
    // Raw value
    rcValue[chan] = val;

1020 1021 1022
    // Normalized value
    float normalized;

1023
    if (val >= rcTrim[chan]) {
1024
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
1025
    }
1026
    else {
1027 1028 1029 1030 1031 1032 1033
        normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]);
    }

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

1035
    if (chan == rcMapping[0]) {
1036
        // ROLL
1037
        rcRoll = normalized;
1038
    }
1039
    if (chan == rcMapping[1]) {
1040
        // PITCH
1041
        rcPitch = normalized;
1042
    }
1043
    if (chan == rcMapping[2]) {
1044
        rcYaw = normalized;
1045
    }
1046
    if (chan == rcMapping[3]) {
1047
        // THROTTLE
1048 1049 1050 1051
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
1052
        }
1053 1054

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
1055
    }
1056
    if (chan == rcMapping[4]) {
1057
        // MODE SWITCH
1058
        rcMode = normalized;
1059
    }
1060
    if (chan == rcMapping[5]) {
1061
        // AUX1
1062
        rcAux1 = normalized;
1063
    }
1064
    if (chan == rcMapping[6]) {
1065
        // AUX2
1066
        rcAux2 = normalized;
1067
    }
1068
    if (chan == rcMapping[7]) {
1069
        // AUX3
1070
        rcAux3 = normalized;
1071 1072 1073 1074
    }

    changed = true;

1075
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
1076 1077
}

1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110
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;
    }
}

1111 1112 1113 1114
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
1115 1116
    if (!doneLoadingConfig)
    {
1117 1118
        //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.
1119 1120
        return;
    }
1121

1122
    if (paramToWidgetMap.contains(parameterName))
1123
    {
1124
        //Main group of parameters of the selected airframe
1125 1126
        paramToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName)))
1127
        {
1128
            toolToBoxMap[paramToWidgetMap.value(parameterName)]->show();
1129 1130 1131
        }
        else
        {
1132
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1133 1134
        }
    }
1135
    else if (libParamToWidgetMap.contains(parameterName))
1136
    {
1137
        //All the library parameters
1138 1139
        libParamToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName)))
1140
        {
1141
            toolToBoxMap[libParamToWidgetMap.value(parameterName)]->show();
1142 1143 1144
        }
        else
        {
1145
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1146 1147 1148 1149
        }
    }
    else
    {
1150 1151
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
1152 1153 1154 1155 1156
        bool found = false;
        for (int i=0;i<toolWidgets.size();i++)
        {
            if (parameterName.startsWith(toolWidgets[i]->objectName()))
            {
1157
                //It should be grouped with this one, add it.
1158
                toolWidgets[i]->addParam(uas,component,parameterName,value);
1159
                libParamToWidgetMap.insert(parameterName,toolWidgets[i]);
1160 1161 1162 1163 1164 1165
                found  = true;
                break;
            }
        }
        if (!found)
        {
1166
            //New param type, create a QGroupBox for it.
1167
            QWidget* parent;
1168
            if (ui->advancedLeftLayout->count() > ui->advancedRightLayout->count())
1169 1170 1171 1172 1173 1174 1175 1176 1177 1178
            {
                parent = ui->advancedRightContents;
            }
            else
            {
                parent = ui->advancedLeftContents;
            }

            // Create the tool, attaching it to the QGroupBox
            QGCToolWidget *tool = new QGCToolWidget("", parent);
1179 1180 1181 1182 1183 1184 1185 1186
            QString tooltitle = parameterName;
            if (parameterName.split("_").size() > 1)
            {
                tooltitle = parameterName.split("_")[0] + "_";
            }
            tool->setTitle(tooltitle);
            tool->setObjectName(tooltitle);
            //tool->setSettings(set);
1187
            libParamToWidgetMap.insert(parameterName,tool);
1188
            toolWidgets.append(tool);
1189 1190
            tool->addParam(uas, component, parameterName, value);
            QGroupBox *box = new QGroupBox(parent);
1191
            box->setTitle(tool->objectName());
1192
            box->setLayout(new QVBoxLayout(box));
1193 1194
            box->layout()->addWidget(tool);

1195 1196 1197
            libParamToWidgetMap.insert(parameterName,tool);
            toolWidgets.append(tool);

1198 1199
            // Make sure we have similar number of widgets on each side.
            if (ui->advancedLeftLayout->count() > ui->advancedRightLayout->count())
1200
            {
1201
                ui->advancedRightLayout->addWidget(box);
1202 1203 1204
            }
            else
            {
1205
                ui->advancedLeftLayout->addWidget(box);
1206 1207 1208
            }
            toolToBoxMap[tool] = box;
        }
1209
    }
1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225

    // 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;
1226
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1227
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
1228
        if (ok && index < chanMax)
1229 1230
        {
            rcMin[index] = value.toInt();
1231
            updateMinMax();
1232 1233 1234 1235 1236
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
1237 1238
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
        if (ok && index < chanMax)
1239 1240
        {
            rcMax[index] = value.toInt();
1241
            updateMinMax();
1242 1243 1244 1245 1246
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
1247 1248
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
        if (ok && index < chanMax)
1249 1250 1251 1252 1253 1254 1255
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
1256 1257
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
        if (ok && index < chanMax)
1258 1259
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
1260
            updateInvertedCheckboxes(index);
1261 1262 1263 1264 1265 1266 1267 1268
        }
    }

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

1269 1270 1271 1272 1273 1274 1275 1276
    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();
    }
1277 1278 1279 1280

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

    if (parameterName.contains("RC_MAP_ROLL")) {
1281 1282
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
1283
        ui->rollSpinBox->setEnabled(true);
1284 1285 1286
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
1287 1288
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
1289
        ui->pitchSpinBox->setEnabled(true);
1290 1291 1292
    }

    if (parameterName.contains("RC_MAP_YAW")) {
1293 1294
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
1295
        ui->yawSpinBox->setEnabled(true);
1296 1297 1298
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
1299 1300
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
1301
        ui->throttleSpinBox->setEnabled(true);
1302 1303 1304
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
1305 1306
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
1307
        ui->modeSpinBox->setEnabled(true);
1308 1309 1310
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
1311 1312
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
1313
        ui->aux1SpinBox->setEnabled(true);
1314 1315 1316
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
1317
        rcMapping[6] = value.toInt() - 1;
1318
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
1319
        ui->aux2SpinBox->setEnabled(true);
1320 1321 1322
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
1323
        rcMapping[7] = value.toInt() - 1;
1324
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
1325
        ui->aux3SpinBox->setEnabled(true);
1326 1327 1328 1329 1330
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
1331
        rcScaling[0] = value.toFloat();
1332 1333 1334
    }

    if (parameterName.contains("RC_SCALE_PITCH")) {
1335
        rcScaling[1] = value.toFloat();
1336 1337 1338
    }

    if (parameterName.contains("RC_SCALE_YAW")) {
1339
        rcScaling[2] = value.toFloat();
1340 1341 1342
    }

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
1343
        rcScaling[3] = value.toFloat();
1344 1345 1346
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
1347
        rcScaling[4] = value.toFloat();
1348 1349 1350
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
1351
        rcScaling[5] = value.toFloat();
1352 1353 1354
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
1355
        rcScaling[6] = value.toFloat();
1356 1357 1358
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
1359
        rcScaling[7] = value.toFloat();
1360
    }
1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373
}

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()));
}
1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393
void QGCVehicleConfig::updateMinMax()
{
    // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3
    /*ui->rollWidget->setMin(rcMin[0]);
    ui->rollWidget->setMax(rcMax[0]);
    ui->pitchWidget->setMin(rcMin[1]);
    ui->pitchWidget->setMax(rcMax[1]);
    ui->yawWidget->setMin(rcMin[2]);
    ui->yawWidget->setMax(rcMax[2]);
    ui->throttleWidget->setMin(rcMin[3]);
    ui->throttleWidget->setMax(rcMax[3]);
    ui->radio5Widget->setMin(rcMin[4]);
    ui->radio5Widget->setMax(rcMax[4]);
    ui->radio6Widget->setMin(rcMin[5]);
    ui->radio6Widget->setMax(rcMax[5]);
    ui->radio7Widget->setMin(rcMin[6]);
    ui->radio7Widget->setMax(rcMax[6]);
    ui->radio8Widget->setMin(rcMin[7]);
    ui->radio8Widget->setMax(rcMax[7]);*/
}
1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420

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)
    {
1421 1422
        if (rc_mode == RC_MODE_1)
        {
1423 1424 1425 1426
            //ui->rollSlider->setValue(rcRoll * 50 + 50);
            //ui->pitchSlider->setValue(rcThrottle * 100);
            //ui->yawSlider->setValue(rcYaw * 50 + 50);
            //ui->throttleSlider->setValue(rcPitch * 50 + 50);
1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439
            ui->rollWidget->setValue(rcValue[0]);
            ui->throttleWidget->setValue(rcValue[1]);
            ui->yawWidget->setValue(rcValue[2]);
            ui->pitchWidget->setValue(rcValue[3]);

            ui->rollWidget->setMin(rcMin[0]);
            ui->rollWidget->setMax(rcMax[0]);
            ui->throttleWidget->setMin(rcMin[1]);
            ui->throttleWidget->setMax(rcMax[1]);
            ui->yawWidget->setMin(rcMin[2]);
            ui->yawWidget->setMax(rcMax[2]);
            ui->pitchWidget->setMin(rcMin[3]);
            ui->pitchWidget->setMax(rcMax[3]);
1440 1441 1442
        }
        else if (rc_mode == RC_MODE_2)
        {
1443 1444 1445 1446
            //ui->rollSlider->setValue(rcRoll * 50 + 50);
            //ui->pitchSlider->setValue(rcPitch * 50 + 50);
            //ui->yawSlider->setValue(rcYaw * 50 + 50);
            //ui->throttleSlider->setValue(rcThrottle * 100);
1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459
            ui->rollWidget->setValue(rcValue[0]);
            ui->pitchWidget->setValue(rcValue[1]);
            ui->yawWidget->setValue(rcValue[2]);
            ui->throttleWidget->setValue(rcValue[3]);

            ui->rollWidget->setMin(rcMin[0]);
            ui->rollWidget->setMax(rcMax[0]);
            ui->pitchWidget->setMin(rcMin[1]);
            ui->pitchWidget->setMax(rcMax[1]);
            ui->yawWidget->setMin(rcMin[2]);
            ui->yawWidget->setMax(rcMax[2]);
            ui->throttleWidget->setMin(rcMin[3]);
            ui->throttleWidget->setMax(rcMax[3]);
1460 1461 1462
        }
        else if (rc_mode == RC_MODE_3)
        {
1463 1464 1465 1466
            //ui->rollSlider->setValue(rcYaw * 50 + 50);
            //ui->pitchSlider->setValue(rcThrottle * 100);
            //ui->yawSlider->setValue(rcRoll * 50 + 50);
            //ui->throttleSlider->setValue(rcPitch * 50 + 50);
1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479
            ui->yawWidget->setValue(rcValue[0]);
            ui->throttleWidget->setValue(rcValue[1]);
            ui->rollWidget->setValue(rcValue[2]);
            ui->pitchWidget->setValue(rcValue[3]);

            ui->yawWidget->setMin(rcMin[0]);
            ui->yawWidget->setMax(rcMax[0]);
            ui->throttleWidget->setMin(rcMin[1]);
            ui->throttleWidget->setMax(rcMax[1]);
            ui->rollWidget->setMin(rcMin[2]);
            ui->rollWidget->setMax(rcMax[2]);
            ui->pitchWidget->setMin(rcMin[3]);
            ui->pitchWidget->setMax(rcMax[3]);
1480 1481 1482
        }
        else if (rc_mode == RC_MODE_4)
        {
1483 1484 1485 1486
            //ui->rollSlider->setValue(rcYaw * 50 + 50);
            //ui->pitchSlider->setValue(rcPitch * 50 + 50);
            //ui->yawSlider->setValue(rcRoll * 50 + 50);
            //ui->throttleSlider->setValue(rcThrottle * 100);
1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507
            ui->yawWidget->setValue(rcValue[0]);
            ui->pitchWidget->setValue(rcValue[1]);
            ui->rollWidget->setValue(rcValue[2]);
            ui->throttleWidget->setValue(rcValue[3]);

            ui->yawWidget->setMin(rcMin[0]);
            ui->yawWidget->setMax(rcMax[0]);
            ui->pitchWidget->setMin(rcMin[1]);
            ui->pitchWidget->setMax(rcMax[1]);
            ui->rollWidget->setMin(rcMin[2]);
            ui->rollWidget->setMax(rcMax[2]);
            ui->throttleWidget->setMin(rcMin[3]);
            ui->throttleWidget->setMax(rcMax[3]);
        }
        else if (rc_mode == RC_MODE_NONE)
        {
            ui->rollWidget->setValue(rcValue[0]);
            ui->pitchWidget->setValue(rcValue[1]);
            ui->throttleWidget->setValue(rcValue[2]);
            ui->yawWidget->setValue(rcValue[3]);

1508 1509 1510 1511 1512 1513 1514 1515
            ui->rollWidget->setMin(800);
            ui->rollWidget->setMax(2200);
            ui->pitchWidget->setMin(800);
            ui->pitchWidget->setMax(2200);
            ui->throttleWidget->setMin(800);
            ui->throttleWidget->setMax(2200);
            ui->yawWidget->setMin(800);
            ui->yawWidget->setMax(2200);
1516 1517
        }

1518 1519 1520 1521
        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(' ')));
1522

1523 1524 1525


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

1528 1529 1530 1531 1532 1533 1534
        if (rcValue[rcMapping[4] != UINT16_MAX]) {
            ui->radio5Widget->setValue(rcValue[4]);
            ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
        } else {
            ui->chanLabel_5->setText(tr("---"));
        }

1535
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
1536
            //ui->aux1Slider->setValue(rcAux1 * 50 + 50);
1537
            ui->radio6Widget->setValue(rcValue[5]);
1538
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
1539 1540 1541 1542
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

1543
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
1544
            //ui->aux2Slider->setValue(rcAux2 * 50 + 50);
1545
            ui->radio7Widget->setValue(rcValue[6]);
1546
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
1547 1548 1549 1550
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

1551
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
1552
            //ui->aux3Slider->setValue(rcAux3 * 50 + 50);
1553
            ui->radio8Widget->setValue(rcValue[7]);
1554
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
1555 1556
        } else {
            ui->chanLabel_8->setText(tr("---"));
1557 1558
        }

1559 1560 1561
        changed = false;
    }
}