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

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

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

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

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

48 49 50 51 52 53
    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()));


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

57 58
    ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);

59
    ui->rcCalibrationButton->setCheckable(true);
60 61
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
    connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
62
    connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
    connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));

    /* Connect RC mapping assignments */
    connect(ui->rollSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setRollChan(int)));
    connect(ui->pitchSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setPitchChan(int)));
    connect(ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYawChan(int)));
    connect(ui->throttleSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setThrottleChan(int)));
    connect(ui->modeSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setModeChan(int)));
    connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int)));
    connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(int)));
    connect(ui->aux3SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux3Chan(int)));

    // Connect RC reverse assignments
    connect(ui->invertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setRollInverted(bool)));
    connect(ui->invertCheckBox_2, SIGNAL(clicked(bool)), this, SLOT(setPitchInverted(bool)));
    connect(ui->invertCheckBox_3, SIGNAL(clicked(bool)), this, SLOT(setYawInverted(bool)));
    connect(ui->invertCheckBox_4, SIGNAL(clicked(bool)), this, SLOT(setThrottleInverted(bool)));
    connect(ui->invertCheckBox_5, SIGNAL(clicked(bool)), this, SLOT(setModeInverted(bool)));
    connect(ui->invertCheckBox_6, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool)));
    connect(ui->invertCheckBox_7, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool)));
    connect(ui->invertCheckBox_8, SIGNAL(clicked(bool)), this, SLOT(setAux3Inverted(bool)));
84 85 86 87 88

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

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

89
    for (unsigned int i = 0; i < chanMax; i++)
90
    {
91
        rcValue[i] = UINT16_MAX;
92
        rcMapping[i] = i;
93 94 95 96 97
    }

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
98
}
99 100 101 102 103 104 105 106 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);
}

void QGCVehicleConfig::generalMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-2);
}

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

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

124 125 126 127 128 129 130 131
void QGCVehicleConfig::setRCModeIndex(int newRcMode)
{
    if (newRcMode > 0 && newRcMode < 5)
    {
        rc_mode = (enum RC_MODE) (newRcMode+1);
        changed = true;
    }
}
132 133 134 135 136 137 138 139 140 141 142 143 144

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

145 146
void QGCVehicleConfig::setTrimPositions()
{
Lorenz Meier's avatar
Lorenz Meier committed
147 148 149 150 151 152
    // 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
153
    else if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100)
Lorenz Meier's avatar
Lorenz Meier committed
154 155 156
    {
        rcTrim[rcMapping[3]] = rcMax[rcMapping[3]];   // throttle
    }
157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173
    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

174 175 176 177
    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
178 179 180 181 182 183 184
}

void QGCVehicleConfig::detectChannelInversion()
{

}

185 186 187
void QGCVehicleConfig::startCalibrationRC()
{
    ui->rcTypeComboBox->setEnabled(false);
188
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
189
    resetCalibrationRC();
190
    calibrationEnabled = true;
191 192 193 194
}

void QGCVehicleConfig::stopCalibrationRC()
{
195
    calibrationEnabled = false;
196
    ui->rcTypeComboBox->setEnabled(true);
197
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
198 199
}

200
void QGCVehicleConfig::loadQgcConfig(bool primary)
201
{
202 203 204 205 206 207
    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
208
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
209 210 211 212
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
213
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
214
    }
215 216
    QGCToolWidget *tool;
    bool left = true;
217 218 219 220 221 222 223 224 225 226 227 228
    foreach (QString file,generaldir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
            tool = new QGCToolWidget("", this);
            if (tool->loadSettings(generaldir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
                //ui->sensorLayout->addWidget(tool);
                QGroupBox *box = new QGroupBox(this);
                box->setTitle(tool->objectName());
                box->setLayout(new QVBoxLayout());
                box->layout()->addWidget(tool);
229
                if (left)
230
                {
231 232 233 234 235 236 237
                    left = false;
                    ui->leftGeneralLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->rightGeneralLayout->addWidget(box);
238
                }
239 240 241 242 243
            } else {
                delete tool;
            }
        }
    }
244
    left = true;
245 246 247 248 249 250 251 252 253 254 255 256
    foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
            tool = new QGCToolWidget("", this);
            if (tool->loadSettings(vehicledir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
                //ui->sensorLayout->addWidget(tool);
                QGroupBox *box = new QGroupBox(this);
                box->setTitle(tool->objectName());
                box->setLayout(new QVBoxLayout());
                box->layout()->addWidget(tool);
257
                if (left)
258
                {
259 260 261 262 263 264 265
                    left = false;
                    ui->leftAdvancedLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->rightAdvancedLayout->addWidget(box);
266
                }
267 268 269 270 271 272
            } else {
                delete tool;
            }
        }
    }

273 274 275
    //Load tabs for general configuration
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
276 277 278
        QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3);
        connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
        ui->navBarLayout->insertWidget(2,button);
279
        button->setMinimumHeight(75);
280 281 282 283 284 285 286 287
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
        //QWidget *tab = new QWidget(ui->tabWidget);
        //ui->tabWidget->insertTab(2,tab,dir);
        QWidget *tab = new QWidget(ui->stackedWidget);
        ui->stackedWidget->insertWidget(2,tab);
        buttonToWidgetMap[button] = tab;
288
        tab->setLayout(new QVBoxLayout());
289
        tab->show();
290 291 292 293 294 295 296 297
        QScrollArea *area = new QScrollArea();
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget();
        scrollArea->setLayout(new QVBoxLayout());
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();
298 299 300 301 302 303 304 305 306 307 308 309 310
        QDir newdir = QDir(generaldir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", this);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
                    QGroupBox *box = new QGroupBox(this);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout());
                    box->layout()->addWidget(tool);
311
                    scrollArea->layout()->addWidget(box);
312 313 314 315 316 317 318 319 320 321
                } else {
                    delete tool;
                }
            }
        }
    }

    //Load tabs for vehicle specific configuration
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
322 323 324 325 326 327 328 329 330 331
        //QWidget *tab = new QWidget(ui->tabWidget);
        //ui->tabWidget->insertTab(2,tab,dir);
        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;

332
        button->setMinimumHeight(75);
333 334 335
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
336
        tab->setLayout(new QVBoxLayout());
337
        tab->show();
338 339 340 341 342 343 344 345 346
        QScrollArea *area = new QScrollArea();
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget();
        scrollArea->setLayout(new QVBoxLayout());
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();

347 348 349 350 351 352 353 354 355 356
        QDir newdir = QDir(vehicledir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", this);
                tool->addUAS(mav);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
357
                    QGroupBox *box = new QGroupBox();
358 359 360
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout());
                    box->layout()->addWidget(tool);
361 362 363
                    scrollArea->layout()->addWidget(box);
                    box->show();
                    //gbox->layout()->addWidget(box);
364 365 366 367 368 369
                } else {
                    delete tool;
                }
            }
        }
    }
370 371


372
    // Load calibration
373
    //TODO: Handle this more gracefully, maybe have it scan the directory for multiple calibration entries?
374
    tool = new QGCToolWidget("", this);
375
    tool->addUAS(mav);
376
    if (tool->loadSettings(autopilotdir.absolutePath() + "/general/calibration/calibration.qgw", false))
377 378
    {
        toolWidgets.append(tool);
379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398
        QGroupBox *box = new QGroupBox(this);
        box->setTitle(tool->objectName());
        box->setLayout(new QVBoxLayout());
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
    } else {
        delete tool;
    }


    tool = new QGCToolWidget("", this);
    tool->addUAS(mav);
    if (tool->loadSettings(autopilotdir.absolutePath() + "/" +  mav->getSystemTypeName().toLower() + "/calibration/calibration.qgw", false))
    {
        toolWidgets.append(tool);
        QGroupBox *box = new QGroupBox(this);
        box->setTitle(tool->objectName());
        box->setLayout(new QVBoxLayout());
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
399 400
    } else {
        delete tool;
401
    }
402 403 404 405 406 407 408 409 410 411
    //description.txt
    QFile sensortipsfile(autopilotdir.absolutePath() + "/general/calibration/description.txt");
    sensortipsfile.open(QIODevice::ReadOnly);
    ui->sensorTips->setHtml(sensortipsfile.readAll());
    sensortipsfile.close();





412 413 414 415 416 417 418 419 420 421 422 423 424
}
void QGCVehicleConfig::menuButtonClicked()
{
    QPushButton *button = qobject_cast<QPushButton*>(sender());
    if (!button)
    {
        return;
    }
    if (buttonToWidgetMap.contains(button))
    {
        ui->stackedWidget->setCurrentWidget(buttonToWidgetMap[button]);
    }

425
}
426

427 428 429 430 431 432 433 434 435 436
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
437
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
438 439 440 441
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
442
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
443 444 445 446 447
    }
    qDebug() << autopilotdir.absolutePath();
    qDebug() << generaldir.absolutePath();
    qDebug() << vehicledir.absolutePath();
    QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
448
    if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
449
    {
450
        loadQgcConfig(false);
451
        doneLoadingConfig = true;
452 453
        return;
    }
454
    loadQgcConfig(true);
455 456 457

    QXmlStreamReader xml(xmlfile.readAll());
    xmlfile.close();
458 459

    //TODO: Testing to ensure that incorrectly formated XML won't break this.
460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480
    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();
                            }
481 482 483
                            QVariantMap genset;
                            QVariantMap advset;

484 485
                            QString setname = parametersname;
                            xml.readNext();
486 487
                            int genarraycount = 0;
                            int advarraycount = 0;
488 489 490 491 492 493
                            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();
494 495 496 497 498 499 500 501 502
                                    QString tab= xml.attributes().value("user").toString();
                                    if (tab == "Advanced")
                                    {
                                        advset["title"] = parametersname;
                                    }
                                    else
                                    {
                                        genset["title"] = parametersname;
                                    }
503 504 505 506 507 508 509 510 511 512 513 514 515 516 517
                                    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
518 519 520 521 522 523 524 525 526 527 528 529 530 531
                                            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;
                                            }
532 533 534 535 536 537 538 539 540
                                            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();
541 542 543 544 545 546 547 548 549 550
                                                    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();
                                                    }
551 552 553 554
                                                    paramcount++;
                                                }
                                                xml.readNext();
                                            }
555 556 557 558 559 560 561 562
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
563 564 565 566 567 568 569 570 571 572 573 574
                                        }
                                        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)
                                    {
575
                                        //Nothing inside! Assume it's a value, give it a default range.
576 577
                                        type = 2;
                                        QString fieldtype = "Range";
578
                                        QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
579 580 581 582
                                        fieldmap[fieldtype] = text;
                                    }
                                    if (type == 2)
                                    {
583 584 585 586 587 588 589 590 591 592 593 594 595 596
                                        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;
                                        }
597 598 599 600
                                        if (fieldmap.contains("Range"))
                                        {
                                            float min = 0;
                                            float max = 0;
601
                                            //Some range fields list "0-10" and some list "0 10". Handle both.
602 603 604 605 606 607 608 609 610 611
                                            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();
                                            }
612 613 614 615 616 617 618 619 620 621
                                            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;
                                            }
622 623
                                        }
                                    }
624 625 626 627 628 629 630 631 632 633
                                    if (tab == "Advanced")
                                    {
                                        advarraycount++;
                                        advset["count"] = advarraycount;
                                    }
                                    else
                                    {
                                        genarraycount++;
                                        genset["count"] = genarraycount;
                                    }
634 635 636
                                }
                                xml.readNext();
                            }
637
                            if (genarraycount > 0)
638
                            {
639 640 641 642 643 644 645
                                tool = new QGCToolWidget("", this);
                                tool->addUAS(mav);
                                tool->setTitle(parametersname);
                                tool->setObjectName(parametersname);
                                tool->setSettings(genset);
                                QList<QString> paramlist = tool->getParamList();
                                for (int i=0;i<paramlist.size();i++)
646
                                {
647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
                                        systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
                                        systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
                                        systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
                                    }
                                    else
                                    {
                                        libParamToWidgetMap->insert(paramlist[i],tool);
                                    }
664
                                }
665 666 667 668 669 670 671

                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(this);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout());
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
672
                                {
673
                                    ui->leftGeneralLayout->addWidget(box);
674
                                }
675
                                else if (valuetype == "libraries")
676
                                {
677
                                    ui->rightGeneralLayout->addWidget(box);
678
                                }
679 680 681 682 683 684 685 686 687 688 689 690
                                box->hide();
                                toolToBoxMap[tool] = box;
                            }
                            if (advarraycount > 0)
                            {
                                tool = new QGCToolWidget("", this);
                                tool->addUAS(mav);
                                tool->setTitle(parametersname);
                                tool->setObjectName(parametersname);
                                tool->setSettings(advset);
                                QList<QString> paramlist = tool->getParamList();
                                for (int i=0;i<paramlist.size();i++)
691
                                {
692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
                                        systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
                                        systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
                                        systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
                                    }
                                    else
                                    {
                                        libParamToWidgetMap->insert(paramlist[i],tool);
                                    }
709
                                }
710

711 712 713 714 715 716 717 718 719 720 721 722 723 724 725
                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(this);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout());
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
                                {
                                    ui->leftAdvancedLayout->addWidget(box);
                                }
                                else if (valuetype == "libraries")
                                {
                                    ui->rightAdvancedLayout->addWidget(box);
                                }
                                box->hide();
                                toolToBoxMap[tool] = box;
726
                            }
727 728


729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745


                        }
                        xml.readNext();
                    }

                }

                xml.readNext();
            }
        }
        xml.readNext();
    }
    if (mav)
    {
           mav->getParamManager()->setParamInfo(paramTooltips);
    }
746
    doneLoadingConfig = true;
747
    mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
748 749 750 751 752 753 754 755 756 757 758 759 760 761
}

void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
    // Do nothing if system is the same or NULL
    if ((active == NULL) || mav == active) return;

    if (mav)
    {
        // Disconnect old system
        disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
                   SLOT(remoteControlChannelRawChanged(int,float)));
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
                   SLOT(parameterChanged(int,int,QString,QVariant)));
762 763 764 765 766

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

770 771 772
    // Reset current state
    resetCalibrationRC();

773 774
    chanCount = 0;

775 776
    // Connect new system
    mav = active;
777 778 779 780
    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)));
781

782
    if (systemTypeToParamMap.contains(mav->getSystemTypeName()))
783
    {
784
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
785
    }
786
    else
787
    {
788
        //Indication that we have no meta data for this system type.
789
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
790 791
        systemTypeToParamMap[mav->getSystemTypeName()] = new QMap<QString,QGCToolWidget*>();
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
792 793
    }

794
    if (!paramTooltips.isEmpty())
795
    {
796
           mav->getParamManager()->setParamInfo(paramTooltips);
797 798
    }

799
   //    mav->requestParameters();
800 801 802

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

804 805 806 807

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

    updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
810 811 812 813 814
}
void QGCVehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
815 816
        rcMin[i] = 1200;
        rcMax[i] = 1800;
817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834
    }
}

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

835
    for (unsigned int i = 0; i < chanCount; ++i)
836
    {
837
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
Lorenz Meier's avatar
Lorenz Meier committed
838
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
839
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
840
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
841
        QGC::SLEEP::usleep(50000);
Lorenz Meier's avatar
Lorenz Meier committed
842
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
843 844 845
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
846 847 848
    }

    // Write mappings
849 850 851 852
    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);
853
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
854
    QGC::SLEEP::usleep(50000);
855
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
856 857 858 859 860 861 862 863 864
    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);
865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880
}

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
881
        mav->requestParameter(0, minTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
882
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
883
        mav->requestParameter(0, trimTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
884
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
885
        mav->requestParameter(0, maxTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
886
        QGC::SLEEP::usleep(5000);
Lorenz Meier's avatar
Lorenz Meier committed
887
        mav->requestParameter(0, revTpl.arg(i+1));
Lorenz Meier's avatar
Lorenz Meier committed
888
        QGC::SLEEP::usleep(5000);
889 890 891 892 893 894 895
    }
}

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
896
    mav->writeParametersToStorage();
897 898 899 900
}

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

Bryant's avatar
Bryant committed
905
    if (chan + 1 > (int)chanCount) {
906 907 908 909 910 911 912 913 914 915 916 917 918 919
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
920 921
    }

922 923 924
    // Raw value
    rcValue[chan] = val;

925 926 927 928
    // Normalized value
    float normalized;

    if (val >= rcTrim[chan])
929
    {
930
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
931
    }
932 933 934 935 936 937 938 939 940
    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;
941

942 943 944
    if (chan == rcMapping[0])
    {
        // ROLL
945
        rcRoll = normalized;
946
    }
947
    if (chan == rcMapping[1])
948 949
    {
        // PITCH
950
        rcPitch = normalized;
951
    }
952
    if (chan == rcMapping[2])
953
    {
954
        rcYaw = normalized;
955
    }
956
    if (chan == rcMapping[3])
957 958
    {
        // THROTTLE
959 960 961 962
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
963
        }
964 965

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
966
    }
967
    if (chan == rcMapping[4])
968 969
    {
        // MODE SWITCH
970
        rcMode = normalized;
971
    }
972
    if (chan == rcMapping[5])
973 974
    {
        // AUX1
975
        rcAux1 = normalized;
976
    }
977
    if (chan == rcMapping[6])
978 979
    {
        // AUX2
980
        rcAux2 = normalized;
981
    }
982
    if (chan == rcMapping[7])
983 984
    {
        // AUX3
985
        rcAux3 = normalized;
986 987 988 989
    }

    changed = true;

990
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
991 992
}

993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025
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;
    }
}

1026 1027 1028 1029
void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);
1030 1031
    if (!doneLoadingConfig)
    {
1032 1033
        //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.
1034 1035
        return;
    }
1036

1037 1038
    if (paramToWidgetMap->contains(parameterName))
    {
1039
        //Main group of parameters of the selected airframe
1040 1041 1042 1043 1044 1045 1046
        paramToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(paramToWidgetMap->value(parameterName)))
        {
            toolToBoxMap[paramToWidgetMap->value(parameterName)]->show();
        }
        else
        {
1047
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1048 1049 1050
        }
    }
    else if (libParamToWidgetMap->contains(parameterName))
1051
    {
1052
        //All the library parameters
1053 1054
        libParamToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value);
        if (toolToBoxMap.contains(libParamToWidgetMap->value(parameterName)))
1055
        {
1056
            toolToBoxMap[libParamToWidgetMap->value(parameterName)]->show();
1057 1058 1059
        }
        else
        {
1060
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
1061 1062 1063 1064
        }
    }
    else
    {
1065 1066
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
1067 1068 1069 1070 1071
        bool found = false;
        for (int i=0;i<toolWidgets.size();i++)
        {
            if (parameterName.startsWith(toolWidgets[i]->objectName()))
            {
1072
                //It should be grouped with this one, add it.
1073
                toolWidgets[i]->addParam(uas,component,parameterName,value);
1074
                libParamToWidgetMap->insert(parameterName,toolWidgets[i]);
1075 1076 1077 1078 1079 1080
                found  = true;
                break;
            }
        }
        if (!found)
        {
1081
            //New param type, create a QGroupBox for it.
1082 1083 1084 1085 1086 1087 1088 1089 1090 1091
            QGCToolWidget *tool = new QGCToolWidget("", this);
            QString tooltitle = parameterName;
            if (parameterName.split("_").size() > 1)
            {
                tooltitle = parameterName.split("_")[0] + "_";
            }
            tool->setTitle(tooltitle);
            tool->setObjectName(tooltitle);
            //tool->setSettings(set);
            tool->addParam(uas,component,parameterName,value);
1092
            libParamToWidgetMap->insert(parameterName,tool);
1093 1094 1095 1096 1097 1098
            toolWidgets.append(tool);
            QGroupBox *box = new QGroupBox(this);
            box->setTitle(tool->objectName());
            box->setLayout(new QVBoxLayout());
            box->layout()->addWidget(tool);

1099 1100 1101

            //Make sure we have similar number of widgets on each side.
            if (ui->leftAdvancedLayout->count() > ui->rightAdvancedLayout->count())
1102
            {
1103
                ui->rightAdvancedLayout->addWidget(box);
1104 1105 1106
            }
            else
            {
1107
                ui->leftAdvancedLayout->addWidget(box);
1108 1109 1110
            }
            toolToBoxMap[tool] = box;
        }
1111
    }
1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127

    // Channel calibration values
    QRegExp minTpl("RC?_MIN");
    minTpl.setPatternSyntax(QRegExp::Wildcard);
    QRegExp maxTpl("RC?_MAX");
    maxTpl.setPatternSyntax(QRegExp::Wildcard);
    QRegExp trimTpl("RC?_TRIM");
    trimTpl.setPatternSyntax(QRegExp::Wildcard);
    QRegExp revTpl("RC?_REV");
    revTpl.setPatternSyntax(QRegExp::Wildcard);

    // Do not write the RC type, as these values depend on this
    // active onboard parameter

    if (minTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1128
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1129
        //qDebug() << "PARAM:" << parameterName << "index:" << index;
1130
        if (ok && (index >= 0) && (index < chanMax))
1131 1132 1133 1134 1135 1136 1137
        {
            rcMin[index] = value.toInt();
        }
    }

    if (maxTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1138
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1139
        if (ok && (index >= 0) && (index < chanMax))
1140 1141 1142 1143 1144 1145 1146
        {
            rcMax[index] = value.toInt();
        }
    }

    if (trimTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1147
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1148
        if (ok && (index >= 0) && (index < chanMax))
1149 1150 1151 1152 1153 1154 1155
        {
            rcTrim[index] = value.toInt();
        }
    }

    if (revTpl.exactMatch(parameterName)) {
        bool ok;
Lorenz Meier's avatar
Lorenz Meier committed
1156
        int index = parameterName.mid(2, 1).toInt(&ok) - 1;
1157
        if (ok && (index >= 0) && (index < chanMax))
1158 1159
        {
            rcRev[index] = (value.toInt() == -1) ? true : false;
1160
            updateInvertedCheckboxes(index);
1161 1162 1163 1164 1165 1166 1167 1168
        }
    }

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

1169 1170 1171 1172 1173 1174 1175 1176
    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();
    }
1177 1178 1179 1180

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

    if (parameterName.contains("RC_MAP_ROLL")) {
1181 1182
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
1183 1184 1185
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
1186 1187
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
1188 1189 1190
    }

    if (parameterName.contains("RC_MAP_YAW")) {
1191 1192
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
1193 1194 1195
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
1196 1197
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
1198 1199 1200
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
1201 1202
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
1203 1204 1205
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
1206 1207
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
1208 1209 1210
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
1211
        rcMapping[6] = value.toInt() - 1;
1212
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
1213 1214 1215
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
1216
        rcMapping[7] = value.toInt() - 1;
1217
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
1218 1219 1220 1221 1222
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
1223
        rcScaling[0] = value.toFloat();
1224 1225 1226
    }

    if (parameterName.contains("RC_SCALE_PITCH")) {
1227
        rcScaling[1] = value.toFloat();
1228 1229 1230
    }

    if (parameterName.contains("RC_SCALE_YAW")) {
1231
        rcScaling[2] = value.toFloat();
1232 1233 1234
    }

    if (parameterName.contains("RC_SCALE_THROTTLE")) {
1235
        rcScaling[3] = value.toFloat();
1236 1237 1238
    }

    if (parameterName.contains("RC_SCALE_MODE_SW")) {
1239
        rcScaling[4] = value.toFloat();
1240 1241 1242
    }

    if (parameterName.contains("RC_SCALE_AUX1")) {
1243
        rcScaling[5] = value.toFloat();
1244 1245 1246
    }

    if (parameterName.contains("RC_SCALE_AUX2")) {
1247
        rcScaling[6] = value.toFloat();
1248 1249 1250
    }

    if (parameterName.contains("RC_SCALE_AUX3")) {
1251
        rcScaling[7] = value.toFloat();
1252
    }
1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292
}

void QGCVehicleConfig::updateStatus(const QString& str)
{
    ui->statusLabel->setText(str);
    ui->statusLabel->setStyleSheet("");
}

void QGCVehicleConfig::updateError(const QString& str)
{
    ui->statusLabel->setText(str);
    ui->statusLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name()));
}

void QGCVehicleConfig::setRCType(int type)
{
    if (!mav) return;

    // XXX TODO Add handling of RC_TYPE vs non-RC_TYPE here

    mav->setParameter(0, "RC_TYPE", type);
    rcTypeUpdateRequested = QGC::groundTimeMilliseconds();
    QTimer::singleShot(rcTypeTimeout+100, this, SLOT(checktimeOuts()));
}

void QGCVehicleConfig::checktimeOuts()
{
    if (rcTypeUpdateRequested > 0)
    {
        if (QGC::groundTimeMilliseconds() - rcTypeUpdateRequested > rcTypeTimeout)
        {
            updateError(tr("Setting remote control timed out - is the system connected?"));
        }
    }
}

void QGCVehicleConfig::updateView()
{
    if (changed)
    {
1293 1294
        if (rc_mode == RC_MODE_1)
        {
1295 1296 1297 1298
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
1299 1300 1301
        }
        else if (rc_mode == RC_MODE_2)
        {
1302 1303 1304 1305
            ui->rollSlider->setValue(rcRoll * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcYaw * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
1306 1307 1308
        }
        else if (rc_mode == RC_MODE_3)
        {
1309 1310 1311 1312
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcThrottle * 100);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcPitch * 50 + 50);
1313 1314 1315
        }
        else if (rc_mode == RC_MODE_4)
        {
1316 1317 1318 1319 1320 1321
            ui->rollSlider->setValue(rcYaw * 50 + 50);
            ui->pitchSlider->setValue(rcPitch * 50 + 50);
            ui->yawSlider->setValue(rcRoll * 50 + 50);
            ui->throttleSlider->setValue(rcThrottle * 100);
        }

1322 1323 1324 1325
        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(' ')));
1326 1327

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

1330
        if (rcValue[rcMapping[5]] != UINT16_MAX) {
1331
            ui->aux1Slider->setValue(rcAux1 * 50 + 50);
1332
            ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' ')));
1333 1334 1335 1336
        } else {
            ui->chanLabel_6->setText(tr("---"));
        }

1337
        if (rcValue[rcMapping[6]] != UINT16_MAX) {
1338
            ui->aux2Slider->setValue(rcAux2 * 50 + 50);
1339
            ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' ')));
1340 1341 1342 1343
        } else {
            ui->chanLabel_7->setText(tr("---"));
        }

1344
        if (rcValue[rcMapping[7]] != UINT16_MAX) {
1345
            ui->aux3Slider->setValue(rcAux3 * 50 + 50);
1346
            ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' ')));
1347 1348
        } else {
            ui->chanLabel_8->setText(tr("---"));
1349 1350
        }

1351 1352 1353
        changed = false;
    }
}