QGCPX4VehicleConfig.cc 72.3 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13
// 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
#include <limits.h>
#endif

#include <QTimer>
#include <QDir>
#include <QXmlStreamReader>
#include <QMessageBox>
14
#include <QLabel>
15 16

#include "QGCPX4VehicleConfig.h"
17

18 19
#include "QGC.h"
#include "QGCToolWidget.h"
20
#include "UASManager.h"
21
#include "LinkManager.h"
22
#include "UASParameterCommsMgr.h"
23
#include "ui_QGCPX4VehicleConfig.h"
24
#include "px4_configuration/QGCPX4AirframeConfig.h"
25
#include "px4_configuration/QGCPX4SensorCalibration.h"
26
#include <dialog_bare.h>
tstellanova's avatar
tstellanova committed
27

28 29 30 31 32 33
#define WIDGET_INDEX_FIRMWARE 0
#define WIDGET_INDEX_RC 1
#define WIDGET_INDEX_SENSOR_CAL 2
#define WIDGET_INDEX_AIRFRAME_CONFIG 3
#define WIDGET_INDEX_GENERAL_CONFIG 4
#define WIDGET_INDEX_ADV_CONFIG 5
34 35 36 37

#define MIN_PWM_VAL 800
#define MAX_PWM_VAL 2200

38 39 40 41
QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
    QWidget(parent),
    mav(NULL),
    chanCount(0),
42
    channelWanted(-1),
43
    channelReverseStateWanted(-1),
44 45 46 47 48
    rcRoll(0.0f),
    rcPitch(0.0f),
    rcYaw(0.0f),
    rcThrottle(0.0f),
    rcMode(0.0f),
49 50 51 52
    rcAssist(0.0f),
    rcMission(0.0f),
    rcReturn(0.0f),
    rcFlaps(0.0f),
53 54
    rcAux1(0.0f),
    rcAux2(0.0f),
55
    dataModelChanged(true),
56
    calibrationEnabled(false),
57
    configEnabled(false),
58
    px4AirframeConfig(NULL),
59
    px4SensorCalibration(NULL),
60 61 62
    #ifdef QUPGRADE_SUPPORT
    firmwareDialog(NULL),
    #endif
63 64 65 66
    ui(new Ui::QGCPX4VehicleConfig)
{
    doneLoadingConfig = false;

67 68 69 70
    channelNames << "Roll / Aileron";
    channelNames << "Pitch / Elevator";
    channelNames << "Yaw / Rudder";
    channelNames << "Throttle";
71 72 73 74 75 76
    channelNames << "Main Mode Switch";
    channelNames << "Assist Switch";
    channelNames << "Mission Switch";
    channelNames << "Return Switch";
    channelNames << "Flaps";
    channelNames << "Aux1";
77 78 79 80 81
    channelNames << "Aux2";
    channelNames << "Aux3";
    channelNames << "Aux4";
    channelNames << "Aux5";
    channelNames << "Aux6";
82 83
    channelNames << "Aux7";
    channelNames << "Aux8";
84

85 86 87
    setObjectName("QGC_VEHICLECONFIG");
    ui->setupUi(this);

88 89 90 91
    ui->advancedMenuButton->setEnabled(false);
    ui->airframeMenuButton->setEnabled(false);
    ui->sensorMenuButton->setEnabled(false);
    ui->rcMenuButton->setEnabled(false);
92
    ui->generalMenuButton->hide();
93

94 95 96
    px4AirframeConfig = new QGCPX4AirframeConfig(this);
    ui->airframeLayout->addWidget(px4AirframeConfig);

97 98 99
    px4SensorCalibration = new QGCPX4SensorCalibration(this);
    ui->sensorLayout->addWidget(px4SensorCalibration);

100 101 102
#ifdef QUPGRADE_SUPPORT
    firmwareDialog = new DialogBare(this);
    ui->firmwareLayout->addWidget(firmwareDialog);
103 104 105

    connect(firmwareDialog, SIGNAL(connectLinks()), LinkManager::instance(), SLOT(connectAll()));
    connect(firmwareDialog, SIGNAL(disconnectLinks()), LinkManager::instance(), SLOT(disconnectAll()));
106 107 108 109 110 111 112 113
#else
#error Please check out QUpgrade from http://github.com/LorenzMeier/qupgrade/ into the QGroundControl folder.

    QLabel* label = new QLabel(this);
    label->setText("THIS VERSION OF QGROUNDCONTROL WAS BUILT WITHOUT QUPGRADE. To enable firmware upload support, checkout QUpgrade WITHIN the QGroundControl folder");
    ui->firmwareLayout->addWidget(label);
#endif

114 115 116 117 118 119 120 121 122 123 124 125 126 127 128
    ui->rollWidget->setOrientation(Qt::Horizontal);
    ui->rollWidget->setName("Roll");
    ui->yawWidget->setOrientation(Qt::Horizontal);
    ui->yawWidget->setName("Yaw");
    ui->pitchWidget->setName("Pitch");
    ui->throttleWidget->setName("Throttle");
    ui->radio5Widget->setOrientation(Qt::Horizontal);
    ui->radio5Widget->setName("Radio 5");
    ui->radio6Widget->setOrientation(Qt::Horizontal);
    ui->radio6Widget->setName("Radio 6");
    ui->radio7Widget->setOrientation(Qt::Horizontal);
    ui->radio7Widget->setName("Radio 7");
    ui->radio8Widget->setOrientation(Qt::Horizontal);
    ui->radio8Widget->setName("Radio 8");

129 130 131 132 133 134 135 136 137 138 139 140
    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()));
    connect(ui->airframeMenuButton, SIGNAL(clicked()),
            this, SLOT(airframeMenuButtonClicked()));
    connect(ui->firmwareMenuButton, SIGNAL(clicked()),
            this, SLOT(firmwareMenuButtonClicked()));
141

142 143 144
    connect(ui->advancedCheckBox, SIGNAL(clicked(bool)), ui->advancedGroupBox, SLOT(setVisible(bool)));
    ui->advancedGroupBox->setVisible(false);

145 146
    ui->rcCalibrationButton->setCheckable(true);
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
147

148
    //TODO connect buttons here to save/clear actions?
149 150 151
    UASInterface* tmpMav = UASManager::instance()->getActiveUAS();
    if (tmpMav) {
        ui->pendingCommitsWidget->initWithUAS(tmpMav);
tstellanova's avatar
tstellanova committed
152
        ui->pendingCommitsWidget->update();
153
        setActiveUAS(tmpMav);
tstellanova's avatar
tstellanova committed
154
    }
155

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

159 160 161 162 163 164
    // 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)));
165 166 167 168
    connect(ui->assistSwSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAssistChan(int)));
    connect(ui->missionSwSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setMissionChan(int)));
    connect(ui->returnSwSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setReturnChan(int)));
    connect(ui->flapsSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setFlapsChan(int)));
169 170 171 172 173 174 175 176 177
    connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int)));
    connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(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)));
178 179 180 181 182 183
    connect(ui->assistSwInvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setAssistInverted(bool)));
    connect(ui->missionSwInvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setMissionInverted(bool)));
    connect(ui->returnSwInvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setReturnInverted(bool)));
    connect(ui->flapsInvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setFlapsInverted(bool)));
    connect(ui->aux1InvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool)));
    connect(ui->aux2InvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool)));
184 185 186 187 188 189

    connect(ui->rollButton, SIGNAL(clicked()), this, SLOT(identifyRollChannel()));
    connect(ui->pitchButton, SIGNAL(clicked()), this, SLOT(identifyPitchChannel()));
    connect(ui->yawButton, SIGNAL(clicked()), this, SLOT(identifyYawChannel()));
    connect(ui->throttleButton, SIGNAL(clicked()), this, SLOT(identifyThrottleChannel()));
    connect(ui->modeButton, SIGNAL(clicked()), this, SLOT(identifyModeChannel()));
190 191 192 193
    connect(ui->assistSwButton, SIGNAL(clicked()), this, SLOT(identifyAssistChannel()));
    connect(ui->missionSwButton, SIGNAL(clicked()), this, SLOT(identifyMissionChannel()));
    connect(ui->returnSwButton, SIGNAL(clicked()), this, SLOT(identifyReturnChannel()));
    connect(ui->flapsButton, SIGNAL(clicked()), this, SLOT(identifyFlapsChannel()));
194 195
    connect(ui->aux1Button, SIGNAL(clicked()), this, SLOT(identifyAux1Channel()));
    connect(ui->aux2Button, SIGNAL(clicked()), this, SLOT(identifyAux2Channel()));
196
    connect(ui->persistRcValuesButt,SIGNAL(clicked()), this, SLOT(writeCalibrationRC()));
197

198
    //set rc values to defaults
199
    for (unsigned int i = 0; i < chanMax; i++) {
200
        rcValue[i] = UINT16_MAX;
201
        rcValueReversed[i] = UINT16_MAX;
202
        rcMapping[i] = i;
203
        rcToFunctionMapping[i] = i;
204 205 206
        channelWantedList[i] = (float)UINT16_MAX;//TODO need to clean these up!
        rcMin[i] = 1000.0f;
        rcMax[i] = 2000.0f;
207 208 209 210 211 212 213 214 215 216 217 218 219 220

        // Mapping not established here, so can't pick values via mapping yet!
        rcMappedMin[i] = 1000;
        rcMappedMax[i] = 2000;
        rcMappedValue[i] = UINT16_MAX;
        rcMappedNormalizedValue[i] = 0.0f;
    }

    for (unsigned int i = chanMax -1; i < chanMappedMax; i++) {
        rcMapping[i] = -1;
        rcMappedMin[i] = 1000;
        rcMappedMax[i] = 2000;
        rcMappedValue[i] = UINT16_MAX;
        rcMappedNormalizedValue[i] = 0.0f;
221 222 223 224 225
    }

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
Lorenz Meier's avatar
Lorenz Meier committed
226 227

    firmwareMenuButtonClicked();
228
}
229

230 231 232 233 234
QGCPX4VehicleConfig::~QGCPX4VehicleConfig()
{
    delete ui;
}

235 236
void QGCPX4VehicleConfig::rcMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
237 238
    //TODO eg ui->stackedWidget->findChild("rcConfig");
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_RC);
Lorenz Meier's avatar
Lorenz Meier committed
239
    ui->tabTitleLabel->setText(tr("Radio Calibration"));
240 241 242 243
}

void QGCPX4VehicleConfig::sensorMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
244
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_SENSOR_CAL);
Lorenz Meier's avatar
Lorenz Meier committed
245
    ui->tabTitleLabel->setText(tr("Sensor Calibration"));
246 247 248 249
}

void QGCPX4VehicleConfig::generalMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
250
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_GENERAL_CONFIG);
Lorenz Meier's avatar
Lorenz Meier committed
251
    ui->tabTitleLabel->setText(tr("General Configuration Options"));
252 253 254 255
}

void QGCPX4VehicleConfig::advancedMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
256
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_ADV_CONFIG);
Lorenz Meier's avatar
Lorenz Meier committed
257
    ui->tabTitleLabel->setText(tr("Advanced Configuration Options"));
258 259
}

260 261 262
void QGCPX4VehicleConfig::airframeMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_AIRFRAME_CONFIG);
Lorenz Meier's avatar
Lorenz Meier committed
263
    ui->tabTitleLabel->setText(tr("Airframe Configuration"));
264 265
}

266 267 268
void QGCPX4VehicleConfig::firmwareMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_FIRMWARE);
Lorenz Meier's avatar
Lorenz Meier committed
269
    ui->tabTitleLabel->setText(tr("Firmware Upgrade"));
270 271
}

272 273
void QGCPX4VehicleConfig::identifyChannelMapping(int aert_index)
{
274
    if (chanCount == 0 || aert_index < 0)
275
        return;
276 277

    int oldmapping = rcMapping[aert_index];
278 279
    channelWanted = aert_index;

280
    for (unsigned i = 0; i < chanMax; i++) {
281 282
        if (i >= chanCount) {
            channelWantedList[i] = 0;
283 284
        }
        else {
285 286 287 288
            channelWantedList[i] = rcValue[i];
        }
    }

289 290
    msgBox.setText(tr("Identifying %1 channel").arg(channelNames[channelWanted]));
    msgBox.setInformativeText(tr("Please move stick, switch or potentiometer for the %1 channel\n all the way up/down or left/right.").arg(channelNames[channelWanted]));
291 292 293 294 295 296 297
    msgBox.setStandardButtons(QMessageBox::Ok);
    skipActionButton = msgBox.addButton(tr("Skip"),QMessageBox::RejectRole);
    msgBox.setDefaultButton(QMessageBox::Ok);
    msgBox.exec();
    skipActionButton->hide();
    msgBox.removeButton(skipActionButton);
    if (msgBox.clickedButton() == skipActionButton ){
298 299 300
        channelWanted = -1;
        rcMapping[aert_index] = oldmapping;
    }
301
    skipActionButton = NULL;
302

303 304
}

305 306 307 308 309 310 311 312 313 314 315 316 317 318
void QGCPX4VehicleConfig::toggleCalibrationRC(bool enabled)
{
    if (enabled)
    {
        startCalibrationRC();
    }
    else
    {
        stopCalibrationRC();
    }
}

void QGCPX4VehicleConfig::setTrimPositions()
{
319 320 321 322
    int rollMap = rcMapping[0];
    int pitchMap = rcMapping[1];
    int yawMap = rcMapping[2];
    int throttleMap = rcMapping[3];
323 324 325 326 327

    // Reset all trims, as some might not be touched
    for (unsigned i = 0; i < chanCount; i++) {
        rcTrim[i] = 1500;
    }
328

329
    // Set trim to min if stick is close to min
330 331
    if (abs(rcValue[throttleMap] - rcMin[throttleMap]) < 100) {
        rcTrim[throttleMap] = rcMin[throttleMap];   // throttle
332 333
    }
    // Set trim to max if stick is close to max
334 335
    else if (abs(rcValue[throttleMap] - rcMax[throttleMap]) < 100) {
        rcTrim[throttleMap] = rcMax[throttleMap];   // throttle
336
    }
337
    else  {
338
        // Reject
339 340 341 342 343 344
        QMessageBox warnMsgBox;
        warnMsgBox.setText(tr("Throttle Stick Trim Position Invalid"));
        warnMsgBox.setInformativeText(tr("The throttle stick is not in the min position. Please set it to the minimum value"));
        warnMsgBox.setStandardButtons(QMessageBox::Ok);
        warnMsgBox.setDefaultButton(QMessageBox::Ok);
        (void)warnMsgBox.exec();
345 346 347
    }

    // Set trim for roll, pitch, yaw, throttle
348 349 350 351
    rcTrim[rollMap] = rcValue[rollMap]; // roll
    rcTrim[pitchMap] = rcValue[pitchMap]; // pitch
    rcTrim[yawMap] = rcValue[yawMap]; // yaw

352 353 354 355 356 357 358 359
    // Mode switch and optional modes, might not be mapped (== -1)
    for (unsigned i = 4; i < chanMappedMax; i++) {
        if (rcMapping[i] >= 0 && rcMapping[i] < (int)chanCount) {
            rcTrim[rcMapping[i]] = ((rcMax[rcMapping[i]] - rcMin[rcMapping[i]]) / 2.0f) + rcMin[rcMapping[i]];
        } else if (rcMapping[i] != -1){
            qDebug() << "RC MAPPING FAILED #" << i << "VAL:" << rcMapping[i];
        }
    }
360 361
}

362
void QGCPX4VehicleConfig::detectChannelInversion(int aert_index)
363
{
364 365 366 367 368 369 370 371 372 373 374 375 376 377 378
    if (chanCount == 0 || aert_index < 0 || aert_index >= (int)chanMappedMax)
        return;

    bool oldstatus = rcRev[rcMapping[aert_index]];
    channelReverseStateWanted = aert_index;

    // Reset search list
    for (unsigned i = 0; i < chanMax; i++) {
        if (i >= chanCount) {
            channelReverseStateWantedList[i] = 0;
        }
        else {
            channelReverseStateWantedList[i] = rcValue[i];
        }
    }
379

380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405
    QStringList instructions;
    instructions << "ROLL: Move stick left";
    instructions << "PITCH: Move stick up";
    instructions << "YAW: Move stick left";
    instructions << "THROTTLE: Move stick down";
    instructions << "MODE SWITCH: Push down / towards you";
    instructions << "ASSISTED SWITCH: Push down / towards you";
    instructions << "MISSION SWITCH: Push down / towards you";
    instructions << "RETURN SWITCH: Push down / towards you";
    instructions << "FLAPS: Push down / towards you or turn dial to the leftmost position";
    instructions << "AUX1: Push down / towards you or turn dial to the leftmost position";
    instructions << "AUX2: Push down / towards you or turn dial to the leftmost position";

    msgBox.setText(tr("Identifying DIRECTION of %1 channel").arg(channelNames[channelReverseStateWanted]));
    msgBox.setInformativeText(tr("%2").arg((aert_index < instructions.length()) ? instructions[aert_index] : ""));
    msgBox.setStandardButtons(QMessageBox::Ok);
    skipActionButton = msgBox.addButton(tr("Skip"),QMessageBox::RejectRole);
    msgBox.setDefaultButton(QMessageBox::Ok);
    msgBox.exec();
    skipActionButton->hide();
    msgBox.removeButton(skipActionButton);
    if (msgBox.clickedButton() == skipActionButton ){
        channelReverseStateWanted = -1;
        rcRev[rcMapping[aert_index]] = oldstatus;
    }
    skipActionButton = NULL;
406 407 408 409
}

void QGCPX4VehicleConfig::startCalibrationRC()
{
410 411
    configEnabled = true;
    QMessageBox::warning(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and receiver are powered and connected.\nRESET ALL TRIMS TO CENTER!\n\nDo not move the RC sticks, then click OK to confirm");
412

413 414
    //go ahead and try to map first 8 channels, now that user can skip channels
    for (int i = 0; i < 8; i++) {
415 416 417
        identifyChannelMapping(i);
    }

418 419 420 421
    // Try to identify inverted channels, but only for R/P/Y/T
    for (int i = 0; i < 4; i++) {
        detectChannelInversion(i);
    }
422

423 424
    //QMessageBox::information(0,"Information","Additional channels have not been mapped, but can be mapped in the channel table below.");
    configEnabled = false;
425
    QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
426
    ui->rcCalibrationButton->setText(tr("Save RC Calibration"));
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441
    resetCalibrationRC();
    calibrationEnabled = true;
    ui->rollWidget->showMinMax();
    ui->pitchWidget->showMinMax();
    ui->yawWidget->showMinMax();
    ui->throttleWidget->showMinMax();
    ui->radio5Widget->showMinMax();
    ui->radio6Widget->showMinMax();
    ui->radio7Widget->showMinMax();
    ui->radio8Widget->showMinMax();
}

void QGCPX4VehicleConfig::stopCalibrationRC()
{
    QMessageBox::information(0,"Trims","Ensure all sticks are centeres and throttle is in the downmost position, click OK to continue");
442

443
    calibrationEnabled = false;
444
    configEnabled = false;
445
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
446

447 448 449 450 451 452 453 454
    ui->rollWidget->hideMinMax();
    ui->pitchWidget->hideMinMax();
    ui->yawWidget->hideMinMax();
    ui->throttleWidget->hideMinMax();
    ui->radio5Widget->hideMinMax();
    ui->radio6Widget->hideMinMax();
    ui->radio7Widget->hideMinMax();
    ui->radio8Widget->hideMinMax();
455

456 457
    for (unsigned int i = 0; i < chanCount; i++) {
        if (rcMin[i] > 1350) {
458
            rcMin[i] = 1000;
459
        }
460

461
        if (rcMax[i] < 1650) {
462
            rcMax[i] = 2000;
463
        }
464 465
    }

466 467 468
    qDebug() << "SETTING TRIM";
    setTrimPositions();

469 470
    QString statusstr;
    statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n";
471
    statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading 1000, 1500, 2000\n\n";
472 473
    statusstr += "Channel\tMin\tCenter\tMax\n";
    statusstr += "--------------------\n";
474
    for (unsigned int i=0; i < chanCount; i++) {
475
        statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n";
476
    }
477 478 479 480 481 482 483 484 485


    msgBox.setText(tr("Confirm Calibration"));
    msgBox.setInformativeText(statusstr);
    msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);//allow user to cancel upload after reviewing values
    int msgBoxResult = msgBox.exec();
    if (QMessageBox::Cancel == msgBoxResult) {
        return;//don't commit these values
    }
486

487 488
    QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored.");
    writeCalibrationRC();
489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538
}

void QGCPX4VehicleConfig::loadQgcConfig(bool primary)
{
    Q_UNUSED(primary);
    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
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
    }

    // Generate widgets for the General tab.
    QGCToolWidget *tool;
    bool left = true;
    foreach (QString file,generaldir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
            QWidget* parent = left?ui->generalLeftContents:ui->generalRightContents;
            tool = new QGCToolWidget("", parent);
            if (tool->loadSettings(generaldir.absoluteFilePath(file), false))
            {
                toolWidgets.append(tool);
                QGroupBox *box = new QGroupBox(parent);
                box->setTitle(tool->objectName());
                box->setLayout(new QVBoxLayout(box));
                box->layout()->addWidget(tool);
                if (left)
                {
                    left = false;
                    ui->generalLeftLayout->addWidget(box);
                }
                else
                {
                    left = true;
                    ui->generalRightLayout->addWidget(box);
                }
            } else {
                delete tool;
            }
        }
    }

tstellanova's avatar
tstellanova committed
539

540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561
     //TODO fix and reintegrate the Advanced parameter editor
//    // Generate widgets for the Advanced tab.
//    foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
//    {
//        if (file.toLower().endsWith(".qgw")) {
//            QWidget* parent = ui->advanceColumnContents;
//            tool = new QGCToolWidget("", parent);
//            if (tool->loadSettings(vehicledir.absoluteFilePath(file), false))
//            {
//                toolWidgets.append(tool);
//                QGroupBox *box = new QGroupBox(parent);
//                box->setTitle(tool->objectName());
//                box->setLayout(new QVBoxLayout(box));
//                box->layout()->addWidget(tool);
//                ui->advancedColumnLayout->addWidget(box);

//            } else {
//                delete tool;
//            }
//        }
//    }

562 563 564 565

    // Load tabs for general configuration
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
566
        QPushButton *button = new QPushButton(this);
567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609
        connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
        ui->navBarLayout->insertWidget(2,button);
        button->setMinimumHeight(75);
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
        QWidget *tab = new QWidget(ui->stackedWidget);
        ui->stackedWidget->insertWidget(2,tab);
        buttonToWidgetMap[button] = tab;
        tab->setLayout(new QVBoxLayout());
        tab->show();
        QScrollArea *area = new QScrollArea(tab);
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget(tab);
        scrollArea->setLayout(new QVBoxLayout(tab));
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();
        QDir newdir = QDir(generaldir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", tab);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
                    QGroupBox *box = new QGroupBox(tab);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout(tab));
                    box->layout()->addWidget(tool);
                    scrollArea->layout()->addWidget(box);
                } else {
                    delete tool;
                }
            }
        }
    }

    // Load additional tabs for vehicle specific configuration
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
610
        QPushButton *button = new QPushButton(this);
611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 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 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 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 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998
        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;

        button->setMinimumHeight(75);
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
        tab->setLayout(new QVBoxLayout());
        tab->show();
        QScrollArea *area = new QScrollArea(tab);
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget(tab);
        scrollArea->setLayout(new QVBoxLayout(tab));
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();

        QDir newdir = QDir(vehicledir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", tab);
                tool->addUAS(mav);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
                    QGroupBox *box = new QGroupBox(tab);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout(box));
                    box->layout()->addWidget(tool);
                    scrollArea->layout()->addWidget(box);
                    box->show();
                    //gbox->layout()->addWidget(box);
                } else {
                    delete tool;
                }
            }
        }
    }
}
void QGCPX4VehicleConfig::menuButtonClicked()
{
    QPushButton *button = qobject_cast<QPushButton*>(sender());
    if (!button)
    {
        return;
    }
    if (buttonToWidgetMap.contains(button))
    {
        ui->stackedWidget->setCurrentWidget(buttonToWidgetMap[button]);
    }

}

void QGCPX4VehicleConfig::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
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
    }
    qDebug() << autopilotdir.absolutePath();
    qDebug() << generaldir.absolutePath();
    qDebug() << vehicledir.absolutePath();
    QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
    if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
    {
        loadQgcConfig(false);
        doneLoadingConfig = true;
        return;
    }
    loadQgcConfig(true);

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

    //TODO: Testing to ensure that incorrectly formatted XML won't break this.
    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();
                            }
                            QVariantMap genset;
                            QVariantMap advset;

                            QString setname = parametersname;
                            xml.readNext();
                            int genarraycount = 0;
                            int advarraycount = 0;
                            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();
                                    QString tab= xml.attributes().value("user").toString();
                                    if (tab == "Advanced")
                                    {
                                        advset["title"] = parametersname;
                                    }
                                    else
                                    {
                                        genset["title"] = parametersname;
                                    }
                                    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
                                            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;
                                            }
                                            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();
                                                    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();
                                                    }
                                                    paramcount++;
                                                }
                                                xml.readNext();
                                            }
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                        }
                                        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)
                                    {
                                        //Nothing inside! Assume it's a value, give it a default range.
                                        type = 2;
                                        QString fieldtype = "Range";
                                        QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
                                        fieldmap[fieldtype] = text;
                                    }
                                    if (type == 2)
                                    {
                                        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;
                                        }
                                        if (fieldmap.contains("Range"))
                                        {
                                            float min = 0;
                                            float max = 0;
                                            //Some range fields list "0-10" and some list "0 10". Handle both.
                                            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();
                                            }
                                            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;
                                            }
                                        }
                                    }
                                    if (tab == "Advanced")
                                    {
                                        advarraycount++;
                                        advset["count"] = advarraycount;
                                    }
                                    else
                                    {
                                        genarraycount++;
                                        genset["count"] = genarraycount;
                                    }
                                }
                                xml.readNext();
                            }
                            if (genarraycount > 0)
                            {
                                QWidget* parent = this;
                                if (valuetype == "vehicles")
                                {
                                    parent = ui->generalLeftContents;
                                }
                                else if (valuetype == "libraries")
                                {
                                    parent = ui->generalRightContents;
                                }
                                tool = new QGCToolWidget("", parent);
                                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++)
                                {
                                    //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);
                                    }
                                }

                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(parent);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout(box));
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
                                {
                                    ui->generalLeftLayout->addWidget(box);
                                }
                                else if (valuetype == "libraries")
                                {
                                    ui->generalRightLayout->addWidget(box);
                                }
                                box->hide();
                                toolToBoxMap[tool] = box;
                            }
                            if (advarraycount > 0)
                            {
                                QWidget* parent = this;
                                if (valuetype == "vehicles")
                                {
                                    parent = ui->generalLeftContents;
                                }
                                else if (valuetype == "libraries")
                                {
                                    parent = ui->generalRightContents;
                                }
                                tool = new QGCToolWidget("", parent);
                                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++)
                                {
                                    //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);
                                    }
                                }

                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(parent);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout(box));
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
                                {
                                    ui->generalLeftLayout->addWidget(box);
                                }
                                else if (valuetype == "libraries")
                                {
                                    ui->generalRightLayout->addWidget(box);
                                }
                                box->hide();
                                toolToBoxMap[tool] = box;
                            }
                        }
                        xml.readNext();
                    }
                }
                xml.readNext();
            }
        }
        xml.readNext();
    }

999
    if (!paramTooltips.isEmpty()) {
1000
           paramMgr->setParamDescriptions(paramTooltips);
1001
    }
1002
    doneLoadingConfig = true;
1003
    //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
1004
    paramMgr->requestParameterListIfEmpty();
1005 1006 1007 1008 1009 1010 1011 1012 1013 1014
}

void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
{
    // Hide items if NULL and abort
    if (!active) {
        return;
    }


tstellanova's avatar
tstellanova committed
1015 1016 1017
    // Do nothing if UAS is already visible
    if (mav == active)
        return;
1018 1019 1020

    if (mav)
    {
1021

1022 1023 1024
        // Disconnect old system
        disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
                   SLOT(remoteControlChannelRawChanged(int,float)));
1025
        //TODO use paramCommsMgr instead
1026 1027 1028 1029
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
                   SLOT(parameterChanged(int,int,QString,QVariant)));

        // Delete all children from all fixed tabs.
1030
        foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>()) {
1031 1032
            child->deleteLater();
        }
1033
        foreach(QWidget* child, ui->generalRightContents->findChildren<QWidget*>()) {
1034 1035
            child->deleteLater();
        }
1036
        foreach(QWidget* child, ui->advanceColumnContents->findChildren<QWidget*>()) {
1037 1038
            child->deleteLater();
        }
1039 1040 1041
//        foreach(QWidget* child, ui->sensorLayout->findChildren<QWidget*>()) {
//            child->deleteLater();
//        }
1042

1043 1044 1045 1046 1047
        foreach(QWidget* child, ui->airframeLayout->findChildren<QWidget*>())
        {
            child->deleteLater();
        }

1048
        // And then delete any custom tabs
1049
        foreach(QWidget* child, additionalTabs) {
1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064
            child->deleteLater();
        }
        additionalTabs.clear();

        toolWidgets.clear();
        paramToWidgetMap.clear();
        libParamToWidgetMap.clear();
        systemTypeToParamMap.clear();
        toolToBoxMap.clear();
        paramTooltips.clear();
    }

    // Connect new system
    mav = active;

1065 1066
    paramMgr = mav->getParamManager();

tstellanova's avatar
tstellanova committed
1067
    ui->pendingCommitsWidget->setUAS(mav);
1068
    ui->paramTreeWidget->setUAS(mav);
tstellanova's avatar
tstellanova committed
1069

1070 1071
    // Reset current state
    resetCalibrationRC();
1072
    //TODO eliminate the separate RC_TYPE call
1073 1074 1075 1076 1077
    mav->requestParameter(0, "RC_TYPE");

    chanCount = 0;

    // Connect new system
1078
    connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
1079
               SLOT(remoteControlChannelRawChanged(int,float)));
1080
    connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
1081
               SLOT(parameterChanged(int,int,QString,QVariant)));
1082

1083

1084
    if (systemTypeToParamMap.contains(mav->getSystemTypeName())) {
1085 1086
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }
1087
    else {
1088 1089 1090 1091 1092
        //Indication that we have no meta data for this system type.
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }

1093
    if (!paramTooltips.isEmpty()) {
1094
           mav->getParamManager()->setParamDescriptions(paramTooltips);
1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105
    }

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

    // Since a system is now connected, enable the VehicleConfig UI.
1106 1107 1108 1109 1110
    // Enable buttons
    ui->advancedMenuButton->setEnabled(true);
    ui->airframeMenuButton->setEnabled(true);
    ui->sensorMenuButton->setEnabled(true);
    ui->rcMenuButton->setEnabled(true);
1111 1112 1113 1114
}

void QGCPX4VehicleConfig::resetCalibrationRC()
{
1115
    for (unsigned int i = 0; i < chanMax; ++i) {
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127
        rcMin[i] = 1500;
        rcMax[i] = 1500;
    }
}

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

1128 1129
    updateStatus(tr("Sending RC configuration and storing to persistent memory."));

1130 1131 1132 1133 1134 1135 1136 1137
    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

1138
    for (unsigned int i = 0; i < chanCount; ++i) {
1139
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
1140 1141 1142 1143
        paramMgr->setPendingParam(0, minTpl.arg(i+1), rcMin[i]);
        paramMgr->setPendingParam(0, trimTpl.arg(i+1), rcTrim[i]);
        paramMgr->setPendingParam(0, maxTpl.arg(i+1), rcMax[i]);
        paramMgr->setPendingParam(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
1144 1145 1146
    }

    // Write mappings
1147 1148 1149 1150 1151
    paramMgr->setPendingParam(0, "RC_MAP_ROLL", (int32_t)(rcMapping[0]+1));
    paramMgr->setPendingParam(0, "RC_MAP_PITCH", (int32_t)(rcMapping[1]+1));
    paramMgr->setPendingParam(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
    paramMgr->setPendingParam(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
    paramMgr->setPendingParam(0, "RC_MAP_MODE_SW", (int32_t)(rcMapping[4]+1));
1152 1153 1154 1155 1156 1157
    paramMgr->setPendingParam(0, "RC_MAP_ASSIST_SW", (int32_t)(rcMapping[5]+1));
    paramMgr->setPendingParam(0, "RC_MAP_MISSIO_SW", (int32_t)(rcMapping[6]+1));
    paramMgr->setPendingParam(0, "RC_MAP_RETURN_SW", (int32_t)(rcMapping[7]+1));
    paramMgr->setPendingParam(0, "RC_MAP_FLAPS", (int32_t)(rcMapping[8]+1));
    paramMgr->setPendingParam(0, "RC_MAP_AUX1", (int32_t)(rcMapping[9]+1));
    paramMgr->setPendingParam(0, "RC_MAP_AUX2", (int32_t)(rcMapping[10]+1));
1158 1159 1160 1161

    //let the param mgr manage sending all the pending RC_foo updates and persisting after
    paramMgr->sendPendingParameters(true);

1162 1163 1164 1165
}

void QGCPX4VehicleConfig::requestCalibrationRC()
{
1166
    paramMgr->requestRcCalibrationParamsUpdate();
1167 1168 1169 1170 1171 1172 1173 1174
}

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

1175
void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float fval)
1176 1177
{
    // Check if index and values are sane
1178
    if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax || fval < 500.0f || fval > 2500.0f)
1179 1180 1181 1182 1183 1184
        return;

    if (chan + 1 > (int)chanCount) {
        chanCount = chan+1;
    }

1185
    // Raw value
1186
    float mappedVal = rcMappedValue[rcToFunctionMapping[chan]];
1187
    float deltaRaw = fabsf(fval - rcValue[chan]);
1188 1189
    float delta = fabsf(fval - mappedVal);
    if (!configEnabled && !calibrationEnabled &&
1190 1191
        (deltaRaw < 12.0f && delta < 12.0f && rcValue[chan] > 800 && rcValue[chan] < 2200))
    {
1192 1193 1194 1195
        //ignore tiny jitter values
        return;
    }
    else {
1196
        rcValue[chan] = fval;
1197 1198
    }

1199

1200 1201
    // Update calibration data
    if (calibrationEnabled) {
1202 1203
        if (fval < rcMin[chan]) {
            rcMin[chan] = fval;
1204
        }
1205 1206
        if (fval > rcMax[chan]) {
            rcMax[chan] = fval;
1207 1208 1209
        }
    }

1210 1211
    if (channelWanted >= 0) {
        // If the first channel moved considerably, pick it
1212
        if (fabsf(channelWantedList[chan] - fval) > 300.0f) {
1213
            rcMapping[channelWanted] = chan;
1214
            updateMappingView(channelWanted);
1215 1216 1217 1218

            int chanFound = channelWanted;
            channelWanted = -1;

1219
            // Confirm found channel
1220 1221 1222 1223 1224 1225
            msgBox.setText(tr("%1 Channel found.").arg(channelNames[chanFound]));
            msgBox.setInformativeText(tr("Found %1 to be on the raw RC channel %2").arg(channelNames[chanFound]).arg(chan + 1));
            msgBox.setStandardButtons(QMessageBox::Ok);
            msgBox.setDefaultButton(QMessageBox::Ok);
            (void)msgBox.exec();

1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261
            // XXX fuse with parameter update handling
            switch (chanFound) {
            case 0:
                ui->rollSpinBox->setValue(chan + 1);
                break;
            case 1:
                ui->pitchSpinBox->setValue(chan + 1);
                break;
            case 2:
                ui->yawSpinBox->setValue(chan + 1);
                break;
            case 3:
                ui->throttleSpinBox->setValue(chan + 1);
                break;
            case 4:
                ui->modeSpinBox->setValue(chan + 1);
                break;
            case 5:
                ui->assistSwSpinBox->setValue(chan + 1);
                break;
            case 6:
                ui->missionSwSpinBox->setValue(chan + 1);
                break;
            case 7:
                ui->returnSwSpinBox->setValue(chan + 1);
                break;
            case 8:
                ui->flapsSpinBox->setValue(chan + 1);
                break;
            case 9:
                ui->aux1SpinBox->setValue(chan + 1);
                break;
            case 10:
                ui->aux2SpinBox->setValue(chan + 1);
                break;
            }
1262 1263
        }
    }
1264

1265 1266
    rcValueReversed[chan] = (rcRev[chan]) ? rcMax[chan] - (fval - rcMin[chan]) : fval;

1267 1268
    // Normalized value
    float normalized;
1269 1270 1271
    float chanTrim = rcTrim[chan];
    if (fval >= rcTrim[chan]) {
        normalized = (fval - chanTrim)/(rcMax[chan] - chanTrim);
1272
    }
1273
    else {
1274
        normalized = -(chanTrim - fval)/(chanTrim - rcMin[chan]);
1275 1276 1277 1278 1279 1280 1281
    }

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

1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294
    // Find correct mapped channel
    for (unsigned int i = 0; i < chanCount; i++) {
        if (chan == rcMapping[i]) {
            rcMappedValue[i] = (rcRev[chan]) ? rcMax[chan] - (fval - rcMin[chan]) : fval;

            // Copy min / max
            rcMappedMin[i] = rcMin[chan];
            rcMappedMax[i] = rcMax[chan];

            rcMappedNormalizedValue[i] = normalized;
        }
    }

1295
    if (chan == rcMapping[0]) {
1296 1297
        rcRoll = normalized;
    }
1298
    else if (chan == rcMapping[1]) {
1299 1300
        rcPitch = normalized;
    }
1301
    else if (chan == rcMapping[2]) {
1302 1303
        rcYaw = normalized;
    }
1304
    else if (chan == rcMapping[3]) {
1305 1306
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
1307 1308
        }
        else {
1309 1310 1311 1312 1313
            rcThrottle = normalized;
        }

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
    }
1314
    else if (chan == rcMapping[4]) {
1315
        rcMode = normalized; // MODE SWITCH
1316
    }
1317
    else if (chan == rcMapping[5]) {
1318
        rcAssist = normalized; // ASSIST SWITCH
1319
    }
1320
    else if (chan == rcMapping[6]) {
1321
        rcMission = normalized; // MISSION SWITCH
1322
    }
1323
    else if (chan == rcMapping[7]) {
1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358
        rcReturn = normalized; // RETURN SWITCH
    }
    else if (chan == rcMapping[8]) {
        rcFlaps = normalized; // FLAPS
    }
    else if (chan == rcMapping[9]) {
        rcAux1 = normalized; // AUX2
    }
    else if (chan == rcMapping[10]) {
        rcAux2 = normalized; // AUX3
    }

    if (channelReverseStateWanted >= 0) {
        // If the *right* channel moved considerably, evaluate it
        if (fabsf(fval - 1500) > 350.0f &&
                rcMapping[channelReverseStateWanted] == chan) {

            // Check if the output is positive
            if (fval > 1750) {
                rcRev[rcMapping[channelReverseStateWanted]] = true;
            } else {
                rcRev[rcMapping[channelReverseStateWanted]] = false;
            }

            unsigned currRevFunc = channelReverseStateWanted;

            channelReverseStateWanted = -1;

            // Confirm found channel
            msgBox.setText(tr("Direction of %1 Channel assigned").arg(channelNames[currRevFunc]));
            msgBox.setInformativeText(tr("%1").arg((rcRev[rcMapping[currRevFunc]]) ? "Reversed channel." : "Did not reverse channel."));
            msgBox.setStandardButtons(QMessageBox::Ok);
            msgBox.setDefaultButton(QMessageBox::Ok);
            (void)msgBox.exec();
        }
1359 1360
    }

1361
    dataModelChanged = true;
1362

1363
    qDebug() << "RC CHAN:" << chan << "PPM:" << fval << "NORMALIZED:" << normalized;
1364 1365
}

1366
void QGCPX4VehicleConfig::updateAllInvertedCheckboxes()
1367
{
1368
    for (unsigned function_index = 0; function_index < chanMappedMax; function_index++) {
1369

1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457
        int rc_input_index = rcMapping[function_index];

        if (rc_input_index < 0 || rc_input_index > chanMax)
            continue;

        // Map index to checkbox.
        // TODO(lm) Would be better to stick the checkboxes into a vector upfront
        switch (function_index)
        {
        case 0:
            ui->invertCheckBox->setChecked(rcRev[rc_input_index]);
            ui->rollWidget->setName(tr("Roll (#%1)").arg(rcMapping[0] + 1));
            break;
        case 1:
            ui->invertCheckBox_2->setChecked(rcRev[rc_input_index]);
            ui->pitchWidget->setName(tr("Pitch (#%1)").arg(rcMapping[1] + 1));
            break;
        case 2:
            ui->invertCheckBox_3->setChecked(rcRev[rc_input_index]);
            ui->yawWidget->setName(tr("Yaw (#%1)").arg(rcMapping[2] + 1));
            break;
        case 3:
            ui->invertCheckBox_4->setChecked(rcRev[rc_input_index]);
            ui->throttleWidget->setName(tr("Throt. (#%1)").arg(rcMapping[3] + 1));
            break;
        case 4:
            ui->invertCheckBox_5->setChecked(rcRev[rc_input_index]);
            //ui->radio5Widget->setName(tr("Mode Switch (#%1)").arg(rcMapping[4] + 1));
            break;
        case 5:
            ui->assistSwInvertCheckBox->setChecked(rcRev[rc_input_index]);
            break;
        case 6:
            ui->missionSwInvertCheckBox->setChecked(rcRev[rc_input_index]);
            break;
        case 7:
            ui->returnSwInvertCheckBox->setChecked(rcRev[rc_input_index]);
            break;
        case 8:
            ui->flapsInvertCheckBox->setChecked(rcRev[rc_input_index]);
            break;
        case 9:
            ui->aux1InvertCheckBox->setChecked(rcRev[rc_input_index]);
            break;
        case 10:
            ui->aux2InvertCheckBox->setChecked(rcRev[rc_input_index]);
            break;
        }
    }
}

void QGCPX4VehicleConfig::updateMappingView(int function_index)
{
    Q_UNUSED(function_index);
    updateAllInvertedCheckboxes();

    QStringList assignments;

    for (unsigned i = 0; i < chanMax; i++) {
        assignments << "";
    }

    for (unsigned i = 0; i < chanMappedMax; i++) {
        if (rcMapping[i] >= 0 && rcMapping[i] < (int)chanMax) {
            assignments.replace(rcMapping[i], assignments[rcMapping[i]].append(QString(" / ").append(channelNames[i])));
        }
    }

    for (unsigned i = 0; i < chanMax; i++) {
        if (assignments[i] == "")
            assignments[i] = "UNUSED";
    }

    for (unsigned i = 0; i < chanMax; i++) {
        switch (i) {
        case 4:
            ui->radio5Widget->setName(tr("%1 (#5)").arg(assignments[4]));
            break;
        case 5:
            ui->radio6Widget->setName(tr("%1 (#6)").arg(assignments[5]));
            break;
        case 6:
            ui->radio7Widget->setName(tr("%1 (#7)").arg(assignments[6]));
            break;
        case 7:
            ui->radio8Widget->setName(tr("%1 (#8)").arg(assignments[7]));
            break;
        }
1458 1459 1460
    }
}

1461 1462 1463 1464 1465 1466 1467 1468
void QGCPX4VehicleConfig::handleRcParameterChange(QString parameterName, QVariant value)
{
    if (parameterName.startsWith("RC_")) {
        if (parameterName.startsWith("RC_MAP_")) {
            //RC Mapping radio channels to meaning
            // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3

            int intValue = value.toInt()  - 1;
1469

1470
            if (parameterName.startsWith("RC_MAP_ROLL")) {
1471
                setChannelToFunctionMapping(0, intValue);
1472 1473 1474 1475
                ui->rollSpinBox->setValue(rcMapping[0]+1);
                ui->rollSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_PITCH")) {
1476
                setChannelToFunctionMapping(1, intValue);
1477 1478 1479 1480
                ui->pitchSpinBox->setValue(rcMapping[1]+1);
                ui->pitchSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_YAW")) {
1481
                setChannelToFunctionMapping(2, intValue);
1482 1483 1484 1485
                ui->yawSpinBox->setValue(rcMapping[2]+1);
                ui->yawSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_THROTTLE")) {
1486
                setChannelToFunctionMapping(3, intValue);
1487 1488 1489 1490
                ui->throttleSpinBox->setValue(rcMapping[3]+1);
                ui->throttleSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_MODE_SW")) {
1491
                setChannelToFunctionMapping(4, intValue);
1492 1493 1494
                ui->modeSpinBox->setValue(rcMapping[4]+1);
                ui->modeSpinBox->setEnabled(true);
            }
1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514
            else if (parameterName.startsWith("RC_MAP_ASSIST_SW")) {
                setChannelToFunctionMapping(5, intValue);
                ui->assistSwSpinBox->setValue(rcMapping[5]+1);
                ui->assistSwSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_MISSIO_SW")) {
                setChannelToFunctionMapping(6, intValue);
                ui->missionSwSpinBox->setValue(rcMapping[6]+1);
                ui->missionSwSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_RETURN_SW")) {
                setChannelToFunctionMapping(7, intValue);
                ui->returnSwSpinBox->setValue(rcMapping[7]+1);
                ui->returnSwSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_FLAPS")) {
                setChannelToFunctionMapping(8, intValue);
                ui->flapsSpinBox->setValue(rcMapping[8]+1);
                ui->flapsSpinBox->setEnabled(true);
            }
1515
            else if (parameterName.startsWith("RC_MAP_AUX1")) {
1516 1517
                setChannelToFunctionMapping(9, intValue);
                ui->aux1SpinBox->setValue(rcMapping[9]+1);
1518 1519 1520
                ui->aux1SpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_AUX2")) {
1521 1522
                setChannelToFunctionMapping(10, intValue);
                ui->aux2SpinBox->setValue(rcMapping[10]+1);
1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537
                ui->aux2SpinBox->setEnabled(true);
            }
        }
        else if (parameterName.startsWith("RC_SCALE_")) {
            // Scaling
            float floatVal = value.toFloat();
            if (parameterName.startsWith("RC_SCALE_ROLL")) {
                rcScaling[0] = floatVal;
            }
            else if (parameterName.startsWith("RC_SCALE_PITCH")) {
                rcScaling[1] = floatVal;
            }
            else if (parameterName.startsWith("RC_SCALE_YAW")) {
                rcScaling[2] = floatVal;
            }
1538 1539 1540 1541 1542 1543 1544 1545 1546 1547
            // Not implemented at this point
//            else if (parameterName.startsWith("RC_SCALE_THROTTLE")) {
//                rcScaling[3] = floatVal;
//            }
//            else if (parameterName.startsWith("RC_SCALE_AUX1")) {
//                rcScaling[5] = floatVal;
//            }
//            else if (parameterName.startsWith("RC_SCALE_AUX2")) {
//                rcScaling[6] = floatVal;
//            }
1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590
        }
    }
    else  {
        // Channel calibration values
        bool ok = false;
        unsigned int index = chanMax;
        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
        int intVal = value.toInt();

        if (minTpl.exactMatch(parameterName)) {
            index = parameterName.mid(2, 1).toInt(&ok) - 1;
            if (ok && index < chanMax) {
                rcMin[index] = intVal;
                updateRcWidgetValues();
            }
        }
        else if (maxTpl.exactMatch(parameterName)) {
            index = parameterName.mid(2, 1).toInt(&ok) - 1;
            if (ok && index < chanMax) {
                rcMax[index] = intVal;
                updateRcWidgetValues();
            }
        }
        else if (trimTpl.exactMatch(parameterName)) {
            index = parameterName.mid(2, 1).toInt(&ok) - 1;
            if (ok && index < chanMax) {
                rcTrim[index] = intVal;
            }
        }
        else if (revTpl.exactMatch(parameterName)) {
            index = parameterName.mid(2, 1).toInt(&ok) - 1;
            if (ok && index < chanMax) {
                rcRev[index] = (intVal == -1) ? true : false;
1591 1592 1593 1594 1595 1596

                for (unsigned i = 0; i < chanMappedMax; i++)
                {
                    if (rcMapping[i] == (int)index)
                        updateMappingView(i);
                }
1597 1598 1599
            }
        }
    }
1600
}
1601

1602 1603 1604 1605 1606 1607 1608
void QGCPX4VehicleConfig::setChannelToFunctionMapping(int function, int channel)
{
    if (function >= 0 && function < (int)chanMappedMax)
        rcMapping[function] = channel;

    if (channel >= 0 && channel < (int)chanMax)
        rcToFunctionMapping[channel] = function;
1609 1610
}

1611 1612
void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
1613
    if (!doneLoadingConfig) {
1614 1615 1616 1617 1618
        //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.
        return;
    }

1619
    //TODO this may introduce a bug with param editor widgets not receiving param updates
1620 1621 1622 1623 1624 1625
    if (parameterName.startsWith("RC")) {
        handleRcParameterChange(parameterName,value);
        return;
    }

    if (paramToWidgetMap.contains(parameterName)) {
1626 1627
        //Main group of parameters of the selected airframe
        paramToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
1628
        if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName))) {
1629 1630
            toolToBoxMap[paramToWidgetMap.value(parameterName)]->show();
        }
1631
        else {
1632 1633 1634
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
        }
    }
1635
    else if (libParamToWidgetMap.contains(parameterName)) {
1636 1637
        //All the library parameters
        libParamToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
1638
        if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName))) {
1639 1640
            toolToBoxMap[libParamToWidgetMap.value(parameterName)]->show();
        }
1641
        else {
1642 1643 1644
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
        }
    }
1645
    else {
1646 1647 1648
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
        bool found = false;
1649 1650
        for (int i=0;i<toolWidgets.size();i++) {
            if (parameterName.startsWith(toolWidgets[i]->objectName())) {
1651 1652 1653 1654 1655 1656 1657
                //It should be grouped with this one, add it.
                toolWidgets[i]->addParam(uas,component,parameterName,value);
                libParamToWidgetMap.insert(parameterName,toolWidgets[i]);
                found  = true;
                break;
            }
        }
1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684
//        if (!found) {
//            //New param type, create a QGroupBox for it.
//            QWidget* parent = ui->advanceColumnContents;

//            // Create the tool, attaching it to the QGroupBox
//            QGCToolWidget *tool = new QGCToolWidget("", parent);
//            QString tooltitle = parameterName;
//            if (parameterName.split("_").size() > 1) {
//                tooltitle = parameterName.split("_")[0] + "_";
//            }
//            tool->setTitle(tooltitle);
//            tool->setObjectName(tooltitle);
//            //tool->setSettings(set);
//            libParamToWidgetMap.insert(parameterName,tool);
//            toolWidgets.append(tool);
//            tool->addParam(uas, component, parameterName, value);
//            QGroupBox *box = new QGroupBox(parent);
//            box->setTitle(tool->objectName());
//            box->setLayout(new QVBoxLayout(box));
//            box->layout()->addWidget(tool);

//            libParamToWidgetMap.insert(parameterName,tool);
//            toolWidgets.append(tool);
//            ui->advancedColumnLayout->addWidget(box);

//            toolToBoxMap[tool] = box;
//        }
1685 1686 1687 1688 1689 1690
    }

}

void QGCPX4VehicleConfig::updateStatus(const QString& str)
{
1691 1692
    ui->advancedStatusLabel->setText(str);
    ui->advancedStatusLabel->setStyleSheet("");
1693 1694 1695 1696
}

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

1701 1702
void QGCPX4VehicleConfig::checktimeOuts()
{
1703

1704 1705
}

1706 1707 1708

void QGCPX4VehicleConfig::updateRcWidgetValues()
{
1709 1710 1711 1712 1713
    ui->rollWidget->setValueAndRange(rcMappedValue[0],rcMappedMin[0],rcMappedMax[0]);
    ui->pitchWidget->setValueAndRange(rcMappedValue[1],rcMappedMin[1],rcMappedMax[1]);
    ui->yawWidget->setValueAndRange(rcMappedValue[2],rcMappedMin[2],rcMappedMax[2]);
    ui->throttleWidget->setValueAndRange(rcMappedValue[3],rcMappedMin[3],rcMappedMax[3]);

1714 1715 1716 1717
    ui->radio5Widget->setValueAndRange(rcValueReversed[4],rcMin[4],rcMax[4]);
    ui->radio6Widget->setValueAndRange(rcValueReversed[5],rcMin[5],rcMax[5]);
    ui->radio7Widget->setValueAndRange(rcValueReversed[6],rcMin[6],rcMax[6]);
    ui->radio8Widget->setValueAndRange(rcValueReversed[7],rcMin[7],rcMax[7]);
1718 1719
}

1720
void QGCPX4VehicleConfig::updateRcChanLabels()
1721
{
1722 1723 1724 1725 1726 1727
    ui->rollChanLabel->setText(labelForRcValue(rcRoll));
    ui->pitchChanLabel->setText(labelForRcValue(rcPitch));
    ui->yawChanLabel->setText(labelForRcValue(rcYaw));
    ui->throttleChanLabel->setText(labelForRcValue(rcThrottle));

    QString blankLabel = tr("---");
1728
    if (rcValue[rcMapping[4]] != UINT16_MAX) {
1729 1730 1731 1732 1733
        ui->modeChanLabel->setText(labelForRcValue(rcMode));
    }
    else {
        ui->modeChanLabel->setText(blankLabel);
    }
1734

1735
    if (rcValue[rcMapping[5]] != UINT16_MAX) {
1736
        ui->assistSwChanLabel->setText(labelForRcValue(rcAssist));
1737 1738
    }
    else {
1739
        ui->assistSwChanLabel->setText(blankLabel);
1740
    }
1741

1742
    if (rcValue[rcMapping[6]] != UINT16_MAX) {
1743
        ui->missionSwChanLabel->setText(labelForRcValue(rcMission));
1744 1745
    }
    else {
1746
        ui->missionSwChanLabel->setText(blankLabel);
1747
    }
1748

1749
    if (rcValue[rcMapping[7]] != UINT16_MAX) {
1750 1751 1752 1753 1754 1755 1756 1757
        ui->returnSwChanLabel->setText(labelForRcValue(rcReturn));
    }
    else {
        ui->returnSwChanLabel->setText(blankLabel);
    }

    if (rcValue[rcMapping[8]] != UINT16_MAX) {
        ui->flapsChanLabel->setText(labelForRcValue(rcFlaps));
1758 1759
    }
    else {
1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774
        ui->flapsChanLabel->setText(blankLabel);
    }

    if (rcValue[rcMapping[9]] != UINT16_MAX) {
        ui->aux1ChanLabel->setText(labelForRcValue(rcAux1));
    }
    else {
        ui->aux1ChanLabel->setText(blankLabel);
    }

    if (rcValue[rcMapping[10]] != UINT16_MAX) {
        ui->aux2ChanLabel->setText(labelForRcValue(rcAux2));
    }
    else {
        ui->aux2ChanLabel->setText(blankLabel);
1775 1776
    }
}
1777

1778 1779 1780 1781
void QGCPX4VehicleConfig::updateView()
{
    if (dataModelChanged) {
        dataModelChanged = false;
1782

1783 1784
        updateRcWidgetValues();
        updateRcChanLabels();
1785 1786
    }
}