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

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

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

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

40
    setObjectName("QGC_VEHICLECONFIG");
41
    ui->setupUi(this);
42

43 44 45 46
    ui->rollWidget->setOrientation(Qt::Horizontal);
    ui->rollWidget->setName("Roll");
    ui->yawWidget->setOrientation(Qt::Horizontal);
    ui->yawWidget->setName("Yaw");
47 48
    ui->pitchWidget->setName("Pitch");
    ui->throttleWidget->setName("Throttle");
49 50 51 52 53 54 55 56 57
    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");

58 59 60 61 62
    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()));

63 64
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

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

    /* 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)));
90 91 92 93 94

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

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

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

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

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

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

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

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

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

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

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

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

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

void QGCVehicleConfig::detectChannelInversion()
{

}

194 195
void QGCVehicleConfig::startCalibrationRC()
{
196 197
    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");
198
    ui->rcTypeComboBox->setEnabled(false);
199
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
200
    resetCalibrationRC();
201
    calibrationEnabled = true;
202 203 204 205 206 207 208 209
    ui->rollWidget->showMinMax();
    ui->pitchWidget->showMinMax();
    ui->yawWidget->showMinMax();
    ui->throttleWidget->showMinMax();
    ui->radio5Widget->showMinMax();
    ui->radio6Widget->showMinMax();
    ui->radio7Widget->showMinMax();
    ui->radio8Widget->showMinMax();
210 211 212 213
}

void QGCVehicleConfig::stopCalibrationRC()
{
214
    QMessageBox::information(0,"Trims","Ensure all sticks are centeres and throttle is in the downmost position, click OK to continue");
215
    calibrationEnabled = false;
216
    ui->rcTypeComboBox->setEnabled(true);
217
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235
    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);
236 237
}

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

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

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

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

360
    // Load additional tabs for vehicle specific configuration
361 362
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
363 364 365 366 367 368 369 370
        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;

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

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

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

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

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

}
460

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

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

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

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

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

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

789
    mav->getParamManager()->setParamDescriptions(paramTooltips);
790
    doneLoadingConfig = true;
791
    mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
792 793 794 795
}

void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
Lorenz Meier's avatar
Lorenz Meier committed
796 797 798 799 800 801 802 803 804 805 806 807 808 809 810
    // 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;
    }


811
    // Do nothing if system is the same
812
    if (mav == active) return;
813 814 815 816 817 818 819 820

    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
821
        disconnect(ui->refreshButton,SIGNAL(clicked()),mav,SLOT(requestParameters()));
822

823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846
        // 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)
847
        {
848
            child->deleteLater();
849
        }
850 851
        additionalTabs.clear();

852
        toolWidgets.clear();
853
        paramToWidgetMap.clear();
854 855 856 857
        libParamToWidgetMap.clear();
        systemTypeToParamMap.clear();
        toolToBoxMap.clear();
        paramTooltips.clear();
858 859
    }

Lorenz Meier's avatar
Lorenz Meier committed
860 861 862
    // Connect new system
    mav = active;

863 864 865
    // Reset current state
    resetCalibrationRC();

Lorenz Meier's avatar
Lorenz Meier committed
866 867 868
    requestCalibrationRC();
    mav->requestParameter(0, "RC_TYPE");

869 870
    chanCount = 0;

871
    // Connect new system
872 873 874 875
    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
876
    connect(ui->refreshButton, SIGNAL(clicked()), active, SLOT(requestParameters()));
877

878
    if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
879
    {
880
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
881
    }
882
    else
883
    {
884
        //Indication that we have no meta data for this system type.
885
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
886
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
887 888
    }

889
    if (!paramTooltips.isEmpty())
890
    {
891
           mav->getParamManager()->setParamDescriptions(paramTooltips);
892 893
    }

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

896 897 898
    //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()));
899 900

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
901 902 903 904 905 906 907 908

    // 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);
909 910 911 912 913
    if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA")
    {
        ui->readButton->hide();
        ui->writeButton->hide();
    }
914
}
915

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

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

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

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

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
987
        mav->requestParameter(0, minTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
988
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
989
        mav->requestParameter(0, trimTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
990
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
991
        mav->requestParameter(0, maxTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
992
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
993
        mav->requestParameter(0, revTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
994
        QGC::SLEEP::usleep(5000);
995 996 997 998 999 1000 1001
    }
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
1002
    mav->writeParametersToStorage();
1003 1004 1005 1006
}

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

Bryant's avatar
Bryant committed
1011
    if (chan + 1 > (int)chanCount) {
1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
1026 1027
    }

1028 1029 1030
    // Raw value
    rcValue[chan] = val;

1031 1032 1033 1034
    // Normalized value
    float normalized;

    if (val >= rcTrim[chan])
1035
    {
1036
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
1037
    }
1038 1039 1040 1041 1042 1043 1044 1045 1046
    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;
1047

1048 1049 1050
    if (chan == rcMapping[0])
    {
        // ROLL
1051
        rcRoll = normalized;
1052
    }
1053
    if (chan == rcMapping[1])
1054 1055
    {
        // PITCH
1056
        rcPitch = normalized;
1057
    }
1058
    if (chan == rcMapping[2])
1059
    {
1060
        rcYaw = normalized;
1061
    }
1062
    if (chan == rcMapping[3])
1063 1064
    {
        // THROTTLE
1065 1066 1067 1068
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
1069
        }
1070 1071

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
1072
    }
1073
    if (chan == rcMapping[4])
1074 1075
    {
        // MODE SWITCH
1076
        rcMode = normalized;
1077
    }
1078
    if (chan == rcMapping[5])
1079 1080
    {
        // AUX1
1081
        rcAux1 = normalized;
1082
    }
1083
    if (chan == rcMapping[6])
1084 1085
    {
        // AUX2
1086
        rcAux2 = normalized;
1087
    }
1088
    if (chan == rcMapping[7])
1089 1090
    {
        // AUX3
1091
        rcAux3 = normalized;
1092 1093 1094 1095
    }

    changed = true;

1096
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
1097 1098
}

1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131
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;
    }
}

1132 1133 1134 1135
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
1136 1137
    if (!doneLoadingConfig)
    {
1138 1139
        //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.
1140 1141
        return;
    }
1142

1143
    if (paramToWidgetMap.contains(parameterName))
1144
    {
1145
        //Main group of parameters of the selected airframe
1146 1147
        paramToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName)))
1148
        {
1149
            toolToBoxMap[paramToWidgetMap.value(parameterName)]->show();
1150 1151 1152
        }
        else
        {
1153
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1154 1155
        }
    }
1156
    else if (libParamToWidgetMap.contains(parameterName))
1157
    {
1158
        //All the library parameters
1159 1160
        libParamToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName)))
1161
        {
1162
            toolToBoxMap[libParamToWidgetMap.value(parameterName)]->show();
1163 1164 1165
        }
        else
        {
1166
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1167 1168 1169 1170
        }
    }
    else
    {
1171 1172
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
1173 1174 1175 1176 1177
        bool found = false;
        for (int i=0;i<toolWidgets.size();i++)
        {
            if (parameterName.startsWith(toolWidgets[i]->objectName()))
            {
1178
                //It should be grouped with this one, add it.
1179
                toolWidgets[i]->addParam(uas,component,parameterName,value);
1180
                libParamToWidgetMap.insert(parameterName,toolWidgets[i]);
1181 1182 1183 1184 1185 1186
                found  = true;
                break;
            }
        }
        if (!found)
        {
1187
            //New param type, create a QGroupBox for it.
1188
            QWidget* parent;
1189
            if (ui->advancedLeftLayout->count() > ui->advancedRightLayout->count())
1190 1191 1192 1193 1194 1195 1196 1197 1198 1199
            {
                parent = ui->advancedRightContents;
            }
            else
            {
                parent = ui->advancedLeftContents;
            }

            // Create the tool, attaching it to the QGroupBox
            QGCToolWidget *tool = new QGCToolWidget("", parent);
1200 1201 1202 1203 1204 1205 1206 1207
            QString tooltitle = parameterName;
            if (parameterName.split("_").size() > 1)
            {
                tooltitle = parameterName.split("_")[0] + "_";
            }
            tool->setTitle(tooltitle);
            tool->setObjectName(tooltitle);
            //tool->setSettings(set);
1208
            libParamToWidgetMap.insert(parameterName,tool);
1209
            toolWidgets.append(tool);
1210 1211
            tool->addParam(uas, component, parameterName, value);
            QGroupBox *box = new QGroupBox(parent);
1212
            box->setTitle(tool->objectName());
1213
            box->setLayout(new QVBoxLayout(box));
1214 1215
            box->layout()->addWidget(tool);

1216 1217 1218
            libParamToWidgetMap.insert(parameterName,tool);
            toolWidgets.append(tool);

1219 1220
            // Make sure we have similar number of widgets on each side.
            if (ui->advancedLeftLayout->count() > ui->advancedRightLayout->count())
1221
            {
1222
                ui->advancedRightLayout->addWidget(box);
1223 1224 1225
            }
            else
            {
1226
                ui->advancedLeftLayout->addWidget(box);
1227 1228 1229
            }
            toolToBoxMap[tool] = box;
        }
1230
    }
1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246

    // 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;
1247
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1248
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
1249
        if (ok && index < chanMax)
1250 1251
        {
            rcMin[index] = value.toInt();
1252
            updateMinMax();
1253 1254 1255 1256 1257
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
1258 1259
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
        if (ok && index < chanMax)
1260 1261
        {
            rcMax[index] = value.toInt();
1262
            updateMinMax();
1263 1264 1265 1266 1267
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
1268 1269
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
        if (ok && index < chanMax)
1270 1271 1272 1273 1274 1275 1276
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
1277 1278
        unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1;
        if (ok && index < chanMax)
1279 1280
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
1281
            updateInvertedCheckboxes(index);
1282 1283 1284 1285 1286 1287 1288 1289
        }
    }

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

1290 1291 1292 1293 1294 1295 1296 1297
    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();
    }
1298 1299 1300 1301

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

    if (parameterName.contains("RC_MAP_ROLL")) {
1302 1303
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
1304
        ui->rollSpinBox->setEnabled(true);
1305 1306 1307
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
1308 1309
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
1310
        ui->pitchSpinBox->setEnabled(true);
1311 1312 1313
    }

    if (parameterName.contains("RC_MAP_YAW")) {
1314 1315
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
1316
        ui->yawSpinBox->setEnabled(true);
1317 1318 1319
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
1320 1321
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
1322
        ui->throttleSpinBox->setEnabled(true);
1323 1324 1325
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
1326 1327
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
1328
        ui->modeSpinBox->setEnabled(true);
1329 1330 1331
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
1332 1333
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
1334
        ui->aux1SpinBox->setEnabled(true);
1335 1336 1337
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
1338
        rcMapping[6] = value.toInt() - 1;
1339
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
1340
        ui->aux2SpinBox->setEnabled(true);
1341 1342 1343
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
1344
        rcMapping[7] = value.toInt() - 1;
1345
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
1346
        ui->aux3SpinBox->setEnabled(true);
1347 1348 1349 1350 1351
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
1352
        rcScaling[0] = value.toFloat();
1353 1354 1355
    }

    if (parameterName.contains("RC_SCALE_PITCH")) {
1356
        rcScaling[1] = value.toFloat();
1357 1358 1359
    }

    if (parameterName.contains("RC_SCALE_YAW")) {
1360
        rcScaling[2] = value.toFloat();
1361 1362 1363
    }

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
1364
        rcScaling[3] = value.toFloat();
1365 1366 1367
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
1368
        rcScaling[4] = value.toFloat();
1369 1370 1371
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
1372
        rcScaling[5] = value.toFloat();
1373 1374 1375
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
1376
        rcScaling[6] = value.toFloat();
1377 1378 1379
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
1380
        rcScaling[7] = value.toFloat();
1381
    }
1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394
}

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()));
}
1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414
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]);*/
}
1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441

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)
    {
1442 1443
        if (rc_mode == RC_MODE_1)
        {
1444 1445 1446 1447
            //ui->rollSlider->setValue(rcRoll * 50 + 50);
            //ui->pitchSlider->setValue(rcThrottle * 100);
            //ui->yawSlider->setValue(rcYaw * 50 + 50);
            //ui->throttleSlider->setValue(rcPitch * 50 + 50);
1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460
            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]);
1461 1462 1463
        }
        else if (rc_mode == RC_MODE_2)
        {
1464 1465 1466 1467
            //ui->rollSlider->setValue(rcRoll * 50 + 50);
            //ui->pitchSlider->setValue(rcPitch * 50 + 50);
            //ui->yawSlider->setValue(rcYaw * 50 + 50);
            //ui->throttleSlider->setValue(rcThrottle * 100);
1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480
            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]);
1481 1482 1483
        }
        else if (rc_mode == RC_MODE_3)
        {
1484 1485 1486 1487
            //ui->rollSlider->setValue(rcYaw * 50 + 50);
            //ui->pitchSlider->setValue(rcThrottle * 100);
            //ui->yawSlider->setValue(rcRoll * 50 + 50);
            //ui->throttleSlider->setValue(rcPitch * 50 + 50);
1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500
            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]);
1501 1502 1503
        }
        else if (rc_mode == RC_MODE_4)
        {
1504 1505 1506 1507
            //ui->rollSlider->setValue(rcYaw * 50 + 50);
            //ui->pitchSlider->setValue(rcPitch * 50 + 50);
            //ui->yawSlider->setValue(rcRoll * 50 + 50);
            //ui->throttleSlider->setValue(rcThrottle * 100);
1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528
            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]);

1529 1530 1531 1532 1533 1534 1535 1536
            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);
1537 1538
        }

1539 1540 1541 1542
        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(' ')));
1543

1544 1545 1546


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

1549 1550 1551 1552 1553 1554 1555
        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("---"));
        }

1556
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
1557
            //ui->aux1Slider->setValue(rcAux1 * 50 + 50);
1558
            ui->radio6Widget->setValue(rcValue[5]);
1559
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
1560 1561 1562 1563
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

1564
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
1565
            //ui->aux2Slider->setValue(rcAux2 * 50 + 50);
1566
            ui->radio7Widget->setValue(rcValue[6]);
1567
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
1568 1569 1570 1571
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

1572
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
1573
            //ui->aux3Slider->setValue(rcAux3 * 50 + 50);
1574
            ui->radio8Widget->setValue(rcValue[7]);
1575
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
1576 1577
        } else {
            ui->chanLabel_8->setText(tr("---"));
1578 1579
        }

1580 1581 1582
        changed = false;
    }
}