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

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

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

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

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

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

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

51
    ui->rcCalibrationButton->setCheckable(true);
52 53
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
    connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
54
    connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75
    connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));

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

    // Connect RC reverse assignments
    connect(ui->invertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setRollInverted(bool)));
    connect(ui->invertCheckBox_2, SIGNAL(clicked(bool)), this, SLOT(setPitchInverted(bool)));
    connect(ui->invertCheckBox_3, SIGNAL(clicked(bool)), this, SLOT(setYawInverted(bool)));
    connect(ui->invertCheckBox_4, SIGNAL(clicked(bool)), this, SLOT(setThrottleInverted(bool)));
    connect(ui->invertCheckBox_5, SIGNAL(clicked(bool)), this, SLOT(setModeInverted(bool)));
    connect(ui->invertCheckBox_6, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool)));
    connect(ui->invertCheckBox_7, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool)));
    connect(ui->invertCheckBox_8, SIGNAL(clicked(bool)), this, SLOT(setAux3Inverted(bool)));
76 77 78 79 80

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

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

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

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

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

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

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

118 119 120
void QGCVehicleConfig::setTrimPositions()
{
    // Set trim for roll, pitch, yaw, throttle
121 122 123
    rcTrim[rcMapping[0]] = rcValue[rcMapping[0]]; // roll
    rcTrim[rcMapping[1]] = rcValue[rcMapping[1]]; // pitch
    rcTrim[rcMapping[2]] = rcValue[rcMapping[2]]; // yaw
Lorenz Meier's avatar
Lorenz Meier committed
124 125 126 127 128 129 130 131 132 133
    // Set trim to min if stick is close to min
    if (abs(rcValue[rcMapping[3]] - rcMin[rcMapping[3]]) < 100)
    {
        rcTrim[rcMapping[3]] = rcMin[rcMapping[3]];   // throttle
    }
    // Set trim to max if stick is close to max
    if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100)
    {
        rcTrim[rcMapping[3]] = rcMax[rcMapping[3]];   // throttle
    }
134 135 136 137
    rcTrim[rcMapping[4]] = ((rcMax[rcMapping[4]] - rcMin[rcMapping[4]]) / 2.0f) + rcMin[rcMapping[4]];   // mode sw
    rcTrim[rcMapping[5]] = ((rcMax[rcMapping[5]] - rcMin[rcMapping[5]]) / 2.0f) + rcMin[rcMapping[5]];   // aux 1
    rcTrim[rcMapping[6]] = ((rcMax[rcMapping[6]] - rcMin[rcMapping[6]]) / 2.0f) + rcMin[rcMapping[6]];   // aux 2
    rcTrim[rcMapping[7]] = ((rcMax[rcMapping[7]] - rcMin[rcMapping[7]]) / 2.0f) + rcMin[rcMapping[7]];   // aux 3
138 139 140 141 142 143 144
}

void QGCVehicleConfig::detectChannelInversion()
{

}

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

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

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

234 235 236 237 238 239
            } else {
                delete tool;
            }
        }
    }

240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303
    //Load tabs for general configuration
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
        QWidget *tab = new QWidget(ui->tabWidget);
        tab->setLayout(new QVBoxLayout());
        ui->tabWidget->insertTab(2,tab,dir);
        tab->show();
        QGroupBox *gbox = new QGroupBox(tab);
        tab->layout()->addWidget(gbox);
        gbox->show();
        gbox->setLayout(new QVBoxLayout());
        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);
                    gbox->layout()->addWidget(box);
                } else {
                    delete tool;
                }
            }
        }
    }

    //Load tabs for vehicle specific configuration
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
        QWidget *tab = new QWidget(ui->tabWidget);
        tab->setLayout(new QVBoxLayout());
        ui->tabWidget->insertTab(2,tab,dir);
        tab->show();
        QGroupBox *gbox = new QGroupBox(tab);
        tab->layout()->addWidget(gbox);
        gbox->show();
        gbox->setLayout(new QVBoxLayout());
        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);
                    QGroupBox *box = new QGroupBox(this);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout());
                    box->layout()->addWidget(tool);
                    gbox->layout()->addWidget(box);
                } else {
                    delete tool;
                }
            }
        }
    }
304 305


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





346
}
347

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

    QXmlStreamReader xml(xmlfile.readAll());
    xmlfile.close();
379 380

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

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

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

632 633 634 635 636 637 638 639 640 641 642 643 644 645 646
                                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;
647
                            }
648 649


650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666


                        }
                        xml.readNext();
                    }

                }

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

671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702
void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
    // Do nothing if system is the same or NULL
    if ((active == NULL) || mav == active) return;

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

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

    // Reset current state
    resetCalibrationRC();

    chanCount = 0;

    // Connect new system
    mav = active;
    connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
               SLOT(remoteControlChannelRawChanged(int,float)));
    connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
               SLOT(parameterChanged(int,int,QString,QVariant)));

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

713 714 715 716 717
    if (!paramTooltips.isEmpty())
    {
           mav->getParamManager()->setParamInfo(paramTooltips);
    }

718
   //    mav->requestParameters();
719 720 721 722 723 724 725 726 727 728 729

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


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

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

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

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

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

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

void QGCVehicleConfig::writeParameters()
{
    updateStatus(tr("Writing all onboard parameters."));
    writeCalibrationRC();
815
    mav->writeParametersToStorage();
816 817 818 819
}

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

Bryant's avatar
Bryant committed
824
    if (chan + 1 > (int)chanCount) {
825 826 827 828 829 830 831 832 833 834 835 836 837 838
        chanCount = chan+1;
    }

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

        if (val > rcMax[chan])
        {
            rcMax[chan] = val;
        }
839 840
    }

841 842 843
    // Raw value
    rcValue[chan] = val;

844 845 846 847
    // Normalized value
    float normalized;

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

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

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

    changed = true;

909
    //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized;
910 911
}

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

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

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

1018 1019 1020

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

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

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

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

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

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

1088 1089 1090 1091 1092 1093 1094 1095
    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();
    }
1096 1097 1098 1099

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

    if (parameterName.contains("RC_MAP_ROLL")) {
1100 1101
        rcMapping[0] = value.toInt() - 1;
        ui->rollSpinBox->setValue(rcMapping[0]+1);
1102 1103 1104
    }

    if (parameterName.contains("RC_MAP_PITCH")) {
1105 1106
        rcMapping[1] = value.toInt() - 1;
        ui->pitchSpinBox->setValue(rcMapping[1]+1);
1107 1108 1109
    }

    if (parameterName.contains("RC_MAP_YAW")) {
1110 1111
        rcMapping[2] = value.toInt() - 1;
        ui->yawSpinBox->setValue(rcMapping[2]+1);
1112 1113 1114
    }

    if (parameterName.contains("RC_MAP_THROTTLE")) {
1115 1116
        rcMapping[3] = value.toInt() - 1;
        ui->throttleSpinBox->setValue(rcMapping[3]+1);
1117 1118 1119
    }

    if (parameterName.contains("RC_MAP_MODE_SW")) {
1120 1121
        rcMapping[4] = value.toInt() - 1;
        ui->modeSpinBox->setValue(rcMapping[4]+1);
1122 1123 1124
    }

    if (parameterName.contains("RC_MAP_AUX1")) {
1125 1126
        rcMapping[5] = value.toInt() - 1;
        ui->aux1SpinBox->setValue(rcMapping[5]+1);
1127 1128 1129
    }

    if (parameterName.contains("RC_MAP_AUX2")) {
1130
        rcMapping[6] = value.toInt() - 1;
1131
        ui->aux2SpinBox->setValue(rcMapping[6]+1);
1132 1133 1134
    }

    if (parameterName.contains("RC_MAP_AUX3")) {
1135
        rcMapping[7] = value.toInt() - 1;
1136
        ui->aux3SpinBox->setValue(rcMapping[7]+1);
1137 1138 1139 1140 1141
    }

    // Scaling

    if (parameterName.contains("RC_SCALE_ROLL")) {
1142
        rcScaling[0] = value.toFloat();
1143 1144 1145
    }

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

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

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

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

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

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

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

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

1241 1242 1243 1244
        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(' ')));
1245 1246

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

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

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

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

1270 1271 1272
        changed = false;
    }
}