QGCPX4VehicleConfig.cc 82.4 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

27
#ifdef QGC_QUPGRADE_ENABLED
28
#include <dialog_bare.h>
29
#endif
tstellanova's avatar
tstellanova committed
30

31 32 33 34 35 36
#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
37 38 39 40

#define MIN_PWM_VAL 800
#define MAX_PWM_VAL 2200

41 42 43 44
QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
    QWidget(parent),
    mav(NULL),
    chanCount(0),
45
    channelWanted(-1),
46
    channelReverseStateWanted(-1),
47 48 49 50 51
    rcRoll(0.0f),
    rcPitch(0.0f),
    rcYaw(0.0f),
    rcThrottle(0.0f),
    rcMode(0.0f),
52
    rcAssist(0.0f),
53
    rcLoiter(0.0f),
54 55
    rcReturn(0.0f),
    rcFlaps(0.0f),
56 57
    rcAux1(0.0f),
    rcAux2(0.0f),
58
    dataModelChanged(true),
59
    calibrationEnabled(false),
60
    configEnabled(false),
61
    px4AirframeConfig(NULL),
Lorenz Meier's avatar
Lorenz Meier committed
62 63
    planeBack(":/files/images/px4/rc/cessna_back.png"),
    planeSide(":/files/images/px4/rc/cessna_side.png"),
Lorenz Meier's avatar
Lorenz Meier committed
64
    px4SensorCalibration(NULL),
65 66 67 68
    ui(new Ui::QGCPX4VehicleConfig)
{
    doneLoadingConfig = false;

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

87 88 89
    setObjectName("QGC_VEHICLECONFIG");
    ui->setupUi(this);

90 91 92 93 94
    ui->advancedMenuButton->setEnabled(false);
    ui->airframeMenuButton->setEnabled(false);
    ui->sensorMenuButton->setEnabled(false);
    ui->rcMenuButton->setEnabled(false);

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

Lorenz Meier's avatar
Lorenz Meier committed
98 99
    // px4SafetyConfig = new QGCPX4SafetyConfig(this);
    // ui->safetyConfigLayout->addWidget(px4SafetyConfig);
100

Lorenz Meier's avatar
Lorenz Meier committed
101 102
    // px4TuningConfig = new QGCPX4TuningConfig(this);
    // ui->tuningLayout->addWidget(px4TuningConfig);
103

Lorenz Meier's avatar
Lorenz Meier committed
104 105
    // px4FlightModeConfig = new QGCPX4FlightModeConfig(this);
    // ui->flightModeLayout->addWidget(px4FlightModeConfig);
106

107 108 109
    px4SensorCalibration = new QGCPX4SensorCalibration(this);
    ui->sensorLayout->addWidget(px4SensorCalibration);

110 111
#ifdef QGC_QUPGRADE_ENABLED
    DialogBare *firmwareDialog = new DialogBare(this);
112
    ui->firmwareLayout->addWidget(firmwareDialog);
113 114 115

    connect(firmwareDialog, SIGNAL(connectLinks()), LinkManager::instance(), SLOT(connectAll()));
    connect(firmwareDialog, SIGNAL(disconnectLinks()), LinkManager::instance(), SLOT(disconnectAll()));
116 117 118 119 120 121 122
#else

    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

123 124 125 126 127 128 129 130 131 132 133 134 135 136
    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");
137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156
    ui->radio9Widget->setOrientation(Qt::Horizontal);
    ui->radio9Widget->setName("Radio 9");
    ui->radio10Widget->setOrientation(Qt::Horizontal);
    ui->radio10Widget->setName("Radio 10");
    ui->radio11Widget->setOrientation(Qt::Horizontal);
    ui->radio11Widget->setName("Radio 11");
    ui->radio12Widget->setOrientation(Qt::Horizontal);
    ui->radio12Widget->setName("Radio 12");
    ui->radio13Widget->setOrientation(Qt::Horizontal);
    ui->radio13Widget->setName("Radio 13");
    ui->radio14Widget->setOrientation(Qt::Horizontal);
    ui->radio14Widget->setName("Radio 14");
    ui->radio15Widget->setOrientation(Qt::Horizontal);
    ui->radio15Widget->setName("Radio 15");
    ui->radio16Widget->setOrientation(Qt::Horizontal);
    ui->radio16Widget->setName("Radio 16");
    ui->radio17Widget->setOrientation(Qt::Horizontal);
    ui->radio17Widget->setName("Radio 17");
    ui->radio18Widget->setOrientation(Qt::Horizontal);
    ui->radio18Widget->setName("Radio 18");
157

158 159
    connect(ui->rcMenuButton,SIGNAL(clicked()),
            this,SLOT(rcMenuButtonClicked()));
160 161
    connect(ui->rcCopyTrimButton, SIGNAL(clicked()),
            this, SLOT(copyAttitudeTrim()));
162 163
    connect(ui->sensorMenuButton,SIGNAL(clicked()),
            this,SLOT(sensorMenuButtonClicked()));
164 165 166 167 168 169
    connect(ui->flightModeMenuButton, SIGNAL(clicked()),
            this, SLOT(flightModeMenuButtonClicked()));
    connect(ui->safetyConfigButton, SIGNAL(clicked()),
            this, SLOT(safetyConfigMenuButtonClicked()));
    connect(ui->tuningMenuButton,SIGNAL(clicked()),
            this,SLOT(tuningMenuButtonClicked()));
170 171 172 173 174 175
    connect(ui->advancedMenuButton,SIGNAL(clicked()),
            this,SLOT(advancedMenuButtonClicked()));
    connect(ui->airframeMenuButton, SIGNAL(clicked()),
            this, SLOT(airframeMenuButtonClicked()));
    connect(ui->firmwareMenuButton, SIGNAL(clicked()),
            this, SLOT(firmwareMenuButtonClicked()));
176

177 178 179 180
    // HIDE THE ADVANCED RC CONFIG MENUS
    // TOO MANY USERS FOOL THEMSELVES WITH IT
    ui->advancedCheckBox->setVisible(false);
    //connect(ui->advancedCheckBox, SIGNAL(clicked(bool)), ui->advancedGroupBox, SLOT(setVisible(bool)));
181 182
    ui->advancedGroupBox->setVisible(false);

183 184
#if 0
    // XXX WIP don't connect signal until completed, otherwise view will show after advanced is turned on and then off
Lorenz Meier's avatar
Lorenz Meier committed
185
    connect(ui->advancedCheckBox, SIGNAL(clicked(bool)), ui->graphicsView, SLOT(setHidden(bool)));
186
    ui->graphicsView->setVisible(true);
Lorenz Meier's avatar
Lorenz Meier committed
187 188 189 190
    ui->graphicsView->setScene(&scene);

    scene.addPixmap(planeBack);
    scene.addPixmap(planeSide);
191
#else
Lorenz Meier's avatar
Lorenz Meier committed
192 193
    // XXX hide while WIP
    ui->graphicsView->hide();
194
#endif
Lorenz Meier's avatar
Lorenz Meier committed
195

196
    ui->rcCalibrationButton->setCheckable(true);
197
    ui->rcCalibrationButton->setEnabled(false);
198
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
199
    ui->spektrumPairButton->setCheckable(false);
200 201
    ui->spektrumPairButton->setEnabled(false);
    connect(ui->spektrumPairButton, SIGNAL(clicked(bool)), this, SLOT(toggleSpektrumPairing(bool)));
202

203
    //TODO connect buttons here to save/clear actions?
204 205 206
    UASInterface* tmpMav = UASManager::instance()->getActiveUAS();
    if (tmpMav) {
        ui->pendingCommitsWidget->initWithUAS(tmpMav);
tstellanova's avatar
tstellanova committed
207
        ui->pendingCommitsWidget->update();
208
        setActiveUAS(tmpMav);
tstellanova's avatar
tstellanova committed
209
    }
210

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

214 215 216 217 218 219
    // 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)));
220 221
    connect(ui->posctlSwSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAssistChan(int)));
    connect(ui->loiterSwSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setMissionChan(int)));
222 223
    connect(ui->returnSwSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setReturnChan(int)));
    connect(ui->flapsSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setFlapsChan(int)));
224 225 226 227 228 229 230 231 232
    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)));
233 234
    connect(ui->posctlSwInvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setAssistInverted(bool)));
    connect(ui->loiterSwInvertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setMissionInverted(bool)));
235 236 237 238
    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)));
239 240 241 242 243 244

    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()));
245 246
    connect(ui->posctlSwButton, SIGNAL(clicked()), this, SLOT(identifyAssistChannel()));
    connect(ui->loiterSwButton, SIGNAL(clicked()), this, SLOT(identifyMissionChannel()));
247 248
    connect(ui->returnSwButton, SIGNAL(clicked()), this, SLOT(identifyReturnChannel()));
    connect(ui->flapsButton, SIGNAL(clicked()), this, SLOT(identifyFlapsChannel()));
249 250
    connect(ui->aux1Button, SIGNAL(clicked()), this, SLOT(identifyAux1Channel()));
    connect(ui->aux2Button, SIGNAL(clicked()), this, SLOT(identifyAux2Channel()));
251
    connect(ui->persistRcValuesButt,SIGNAL(clicked()), this, SLOT(writeCalibrationRC()));
252

253
    //set rc values to defaults
254
    for (unsigned int i = 0; i < chanMax; i++) {
255
        rcValue[i] = UINT16_MAX;
256
        rcValueReversed[i] = UINT16_MAX;
257
        rcMapping[i] = i;
258
        rcToFunctionMapping[i] = i;
259 260 261
        channelWantedList[i] = (float)UINT16_MAX;//TODO need to clean these up!
        rcMin[i] = 1000.0f;
        rcMax[i] = 2000.0f;
262 263 264 265 266

        // Mapping not established here, so can't pick values via mapping yet!
        rcMappedMin[i] = 1000;
        rcMappedMax[i] = 2000;
        rcMappedValue[i] = UINT16_MAX;
Lorenz Meier's avatar
Lorenz Meier committed
267
        rcMappedValueRev[i] = UINT16_MAX;
268 269 270 271 272 273 274 275
        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;
Lorenz Meier's avatar
Lorenz Meier committed
276
        rcMappedValueRev[i] = UINT16_MAX;
277
        rcMappedNormalizedValue[i] = 0.0f;
278 279
    }

280 281
    firmwareMenuButtonClicked();

282 283 284
    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
Lorenz Meier's avatar
Lorenz Meier committed
285

Lorenz Meier's avatar
Lorenz Meier committed
286 287
    ui->rcLabel->setText(tr("NO RADIO CONTROL INPUT DETECTED. PLEASE ENSURE THE TRANSMITTER IS ON."));

288
}
289

290 291 292 293 294
QGCPX4VehicleConfig::~QGCPX4VehicleConfig()
{
    delete ui;
}

295 296
void QGCPX4VehicleConfig::rcMenuButtonClicked()
{
297
    ui->stackedWidget->setCurrentWidget(ui->rcTab);
Lorenz Meier's avatar
Lorenz Meier committed
298
    ui->tabTitleLabel->setText(tr("Radio Calibration"));
299 300 301 302
}

void QGCPX4VehicleConfig::sensorMenuButtonClicked()
{
303
    ui->stackedWidget->setCurrentWidget(ui->sensorTab);
Lorenz Meier's avatar
Lorenz Meier committed
304
    ui->tabTitleLabel->setText(tr("Sensor Calibration"));
305 306
}

307 308
void QGCPX4VehicleConfig::tuningMenuButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
309
    ui->stackedWidget->setCurrentWidget(ui->tuningTab);
310 311 312 313 314 315 316 317 318 319
    ui->tabTitleLabel->setText(tr("Controller Tuning"));
}

void QGCPX4VehicleConfig::flightModeMenuButtonClicked()
{
    ui->stackedWidget->setCurrentWidget(ui->flightModeTab);
    ui->tabTitleLabel->setText(tr("Flight Mode Configuration"));
}

void QGCPX4VehicleConfig::safetyConfigMenuButtonClicked()
320
{
321 322
    ui->stackedWidget->setCurrentWidget(ui->safetyConfigTab);
    ui->tabTitleLabel->setText(tr("Safety Feature Configuration"));
323 324 325 326
}

void QGCPX4VehicleConfig::advancedMenuButtonClicked()
{
327
    ui->stackedWidget->setCurrentWidget(ui->advancedTab);
Lorenz Meier's avatar
Lorenz Meier committed
328
    ui->tabTitleLabel->setText(tr("Advanced Configuration Options"));
329 330
}

331 332
void QGCPX4VehicleConfig::airframeMenuButtonClicked()
{
333
    ui->stackedWidget->setCurrentWidget(ui->airframeTab);
Lorenz Meier's avatar
Lorenz Meier committed
334
    ui->tabTitleLabel->setText(tr("Airframe Configuration"));
335 336
}

337 338
void QGCPX4VehicleConfig::firmwareMenuButtonClicked()
{
339
    ui->stackedWidget->setCurrentWidget(ui->firmwareTab);
Lorenz Meier's avatar
Lorenz Meier committed
340
    ui->tabTitleLabel->setText(tr("Firmware Upgrade"));
341 342
}

343 344
void QGCPX4VehicleConfig::identifyChannelMapping(int aert_index)
{
345
    if (chanCount == 0 || aert_index < 0)
346
        return;
347 348

    int oldmapping = rcMapping[aert_index];
349 350
    channelWanted = aert_index;

351
    for (unsigned i = 0; i < chanMax; i++) {
352 353
        if (i >= chanCount) {
            channelWantedList[i] = 0;
354 355
        }
        else {
356 357 358 359
            channelWantedList[i] = rcValue[i];
        }
    }

360 361 362
    msgBox.setText(tr("Detecting %1 ...\t\t").arg(channelNames[channelWanted]));
    msgBox.setInformativeText(tr("Please move stick, switch or potentiometer for this channel all the way up/down or left/right."));
    msgBox.setStandardButtons(QMessageBox::NoButton);
363 364 365 366 367
    skipActionButton = msgBox.addButton(tr("Skip"),QMessageBox::RejectRole);
    msgBox.exec();
    skipActionButton->hide();
    msgBox.removeButton(skipActionButton);
    if (msgBox.clickedButton() == skipActionButton ){
368 369 370
        channelWanted = -1;
        rcMapping[aert_index] = oldmapping;
    }
371
    skipActionButton = NULL;
372

373 374
}

375 376 377 378 379 380 381 382 383 384 385 386
void QGCPX4VehicleConfig::toggleCalibrationRC(bool enabled)
{
    if (enabled)
    {
        startCalibrationRC();
    }
    else
    {
        stopCalibrationRC();
    }
}

387 388
void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled)
{
389 390
    Q_UNUSED(enabled);
    
391 392
    if (!ui->dsm2RadioButton->isChecked() && !ui->dsmxRadioButton->isChecked()
            && !ui->dsmx8RadioButton->isChecked()) {
Lorenz Meier's avatar
Lorenz Meier committed
393 394 395 396 397 398 399
        // Reject
        QMessageBox warnMsgBox;
        warnMsgBox.setText(tr("Please select a Spektrum Protocol Version"));
        warnMsgBox.setInformativeText(tr("Please select either DSM2 or DSM-X\ndirectly below the pair button,\nbased on the receiver type."));
        warnMsgBox.setStandardButtons(QMessageBox::Ok);
        warnMsgBox.setDefaultButton(QMessageBox::Ok);
        (void)warnMsgBox.exec();
400
        return;
Lorenz Meier's avatar
Lorenz Meier committed
401 402
    }

403
    UASInterface* mav = UASManager::instance()->getActiveUAS();
404 405 406 407 408 409 410 411 412 413
    if (mav) {
        int rxSubType;
        if (ui->dsm2RadioButton->isChecked())
            rxSubType = 0;
        else if (ui->dsmxRadioButton->isChecked())
            rxSubType = 1;
        else // if (ui->dsmx8RadioButton->isChecked())
            rxSubType = 2;
        mav->pairRX(0, rxSubType);
    }
414 415
}

416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442
void QGCPX4VehicleConfig::copyAttitudeTrim() {
    if (configEnabled) {

        QMessageBox warnMsgBox;
        warnMsgBox.setText(tr("Attitude trim denied during RC calibration"));
        warnMsgBox.setInformativeText(tr("Please end the RC calibration before doing attitude trim."));
        warnMsgBox.setStandardButtons(QMessageBox::Ok);
        warnMsgBox.setDefaultButton(QMessageBox::Ok);
        (void)warnMsgBox.exec();
    }

    // Not aborted, but warn user

    msgBox.setText(tr("Confirm Attitude Trim"));
    msgBox.setInformativeText(tr("On clicking OK, the current Roll / Pitch / Yaw stick positions will be set as trim values in auto flight. Do NOT reset your trim values after this step."));
    msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);//allow user to cancel upload after reviewing values
    int msgBoxResult = msgBox.exec();
    if (QMessageBox::Cancel == msgBoxResult) {
        return;
        // do not execute
    }

    mav->startRadioControlCalibration(2);
    QGC::SLEEP::msleep(100);
    mav->endRadioControlCalibration();
}

443 444
void QGCPX4VehicleConfig::setTrimPositions()
{
445 446 447 448
    int rollMap = rcMapping[0];
    int pitchMap = rcMapping[1];
    int yawMap = rcMapping[2];
    int throttleMap = rcMapping[3];
449 450 451 452 453

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

455 456 457 458
    bool throttleDone = false;

    while (!throttleDone) {
        // Set trim to min if stick is close to min
459
        if (abs(rcValue[throttleMap] - rcMin[throttleMap]) < 200) {
460 461 462 463
            rcTrim[throttleMap] = rcMin[throttleMap];   // throttle
            throttleDone = true;
        }
        // Set trim to max if stick is close to max
464
        else if (abs(rcValue[throttleMap] - rcMax[throttleMap]) < 200) {
465 466 467 468 469 470 471 472 473
            rcTrim[throttleMap] = rcMax[throttleMap];   // throttle
            throttleDone = true;
        }
        else
        {
            // Reject
            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 zero throttle position and then click OK."));
474
            warnMsgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Abort);
475
            warnMsgBox.setDefaultButton(QMessageBox::Ok);
476 477 478
            if (warnMsgBox.exec() == QMessageBox::Abort) {
                return;
            }
479 480 481
            // wait long enough to get some data
            QGC::SLEEP::msleep(500);
        }
482 483 484
    }

    // Set trim for roll, pitch, yaw, throttle
485 486 487 488
    rcTrim[rollMap] = rcValue[rollMap]; // roll
    rcTrim[pitchMap] = rcValue[pitchMap]; // pitch
    rcTrim[yawMap] = rcValue[yawMap]; // yaw

489 490 491 492 493 494 495 496
    // 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];
        }
    }
497 498
}

499
void QGCPX4VehicleConfig::detectChannelInversion(int aert_index)
500
{
501 502 503 504 505 506 507 508 509 510 511 512 513 514 515
    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];
        }
    }
516

517 518
    QStringList instructions;
    instructions << "ROLL: Move stick left";
519
    instructions << "PITCH: Move stick down";//matches the other sticks: should cause DECREASE in raw rc channel value when not reversed
520 521 522
    instructions << "YAW: Move stick left";
    instructions << "THROTTLE: Move stick down";
    instructions << "MODE SWITCH: Push down / towards you";
523 524
    instructions << "POSITION CONTROL SWITCH: Push down / towards you";
    instructions << "LOITER SWITCH: Push down / towards you";
525 526 527 528 529
    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";

530
    msgBox.setText(tr("%1 Direction").arg(channelNames[channelReverseStateWanted]));
531
    msgBox.setInformativeText(tr("%2").arg((aert_index < instructions.length()) ? instructions[aert_index] : ""));
532
    msgBox.setStandardButtons(QMessageBox::NoButton);
533 534 535 536 537 538 539 540 541
    skipActionButton = msgBox.addButton(tr("Skip"),QMessageBox::RejectRole);
    msgBox.exec();
    skipActionButton->hide();
    msgBox.removeButton(skipActionButton);
    if (msgBox.clickedButton() == skipActionButton ){
        channelReverseStateWanted = -1;
        rcRev[rcMapping[aert_index]] = oldstatus;
    }
    skipActionButton = NULL;
542 543 544 545
}

void QGCPX4VehicleConfig::startCalibrationRC()
{
546
    if (chanCount < 5 && !mav) {
547 548 549
        QMessageBox::warning(0,
                             tr("RC not Connected"),
                             tr("Is the RC receiver connected and transmitter turned on? Detected %1 radio channels. To operate PX4, you need at least 5 channels. ").arg(chanCount));
Lorenz Meier's avatar
Lorenz Meier committed
550
        ui->rcCalibrationButton->setChecked(false);
551 552 553
        return;
    }

554 555
    // XXX magic number: Set to 1 for radio input disable
    mav->startRadioControlCalibration(1);
556

557 558 559 560 561
    // reset all channel mappings above Ch 5 to invalid/unused value before starting calibration
    for (unsigned int j= 5; j < chanMappedMax; j++) {
        rcMapping[j] = -1;
    }

562
    configEnabled = true;
563 564

    QMessageBox::warning(0,tr("Safety Warning"),
565
                         tr("Starting RC calibration.\n\nEnsure RC transmitter and receiver are powered and connected. It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\nReset transmitter trims to center, then click OK to continue"));
566

567 568
    //go ahead and try to map first 8 channels, now that user can skip channels
    for (int i = 0; i < 8; i++) {
569 570 571
        identifyChannelMapping(i);
    }

572 573
    //QMessageBox::information(0,"Information","Additional channels have not been mapped, but can be mapped in the channel table below.");
    configEnabled = false;
Lorenz Meier's avatar
Lorenz Meier committed
574
    ui->rcCalibrationButton->setText(tr("Finish RC Calibration"));
575 576 577 578 579 580 581 582 583 584
    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();
585 586 587 588 589 590 591 592 593 594
    ui->radio9Widget->showMinMax();
    ui->radio10Widget->showMinMax();
    ui->radio11Widget->showMinMax();
    ui->radio12Widget->showMinMax();
    ui->radio13Widget->showMinMax();
    ui->radio14Widget->showMinMax();
    ui->radio15Widget->showMinMax();
    ui->radio16Widget->showMinMax();
    ui->radio17Widget->showMinMax();
    ui->radio18Widget->showMinMax();
Lorenz Meier's avatar
Lorenz Meier committed
595

596 597 598 599 600 601 602 603 604
    msgBox.setText(tr("Information"));
    msgBox.setInformativeText(tr("Please move the sticks to their extreme positions, including all switches. Then click on the OK button once finished"));
    msgBox.setStandardButtons(QMessageBox::Ok);
    msgBox.show();
    msgBox.move((frameGeometry().width() - msgBox.width()) / 4.0f,(frameGeometry().height() - msgBox.height()) / 1.5f);
    int msgBoxResult = msgBox.exec();
    if (QMessageBox::Ok == msgBoxResult) {
        stopCalibrationRC();
    }
605 606 607 608
}

void QGCPX4VehicleConfig::stopCalibrationRC()
{
Lorenz Meier's avatar
Lorenz Meier committed
609 610 611
    if (!calibrationEnabled)
        return;

612 613 614 615 616 617 618 619 620 621 622 623 624
    // Check where the throttle is
    while (rcValue[rcMapping[3]] < 1300 || rcValue[rcMapping[3]] > 1700) {
        // Force user to center the throttle
        msgBox.setText(tr("Please center the throttle stick"));
        msgBox.setInformativeText(tr("The stick should be roughly centered - the exact position is not relevant."));
        msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);//allow user to cancel upload after reviewing values
        int msgBoxResult = msgBox.exec();

        if (QMessageBox::Cancel == msgBoxResult) {
            return; // abort
        }
    }

Lorenz Meier's avatar
Lorenz Meier committed
625 626 627 628 629
    // Try to identify inverted channels, but only for R/P/Y/T
    for (int i = 0; i < 4; i++) {
        detectChannelInversion(i);
    }

630
    QMessageBox::information(0,"Trims","Ensure THROTTLE is in the LOW THROTTLE / MOTOR OFF position and roll / pitch / yaw are CENTERED. Click OK to continue");
631

632
    calibrationEnabled = false;
633
    configEnabled = false;
634
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
635 636 637
    ui->rcCalibrationButton->blockSignals(true);
    ui->rcCalibrationButton->setChecked(false);
    ui->rcCalibrationButton->blockSignals(false);
638

639 640 641 642 643 644 645 646
    ui->rollWidget->hideMinMax();
    ui->pitchWidget->hideMinMax();
    ui->yawWidget->hideMinMax();
    ui->throttleWidget->hideMinMax();
    ui->radio5Widget->hideMinMax();
    ui->radio6Widget->hideMinMax();
    ui->radio7Widget->hideMinMax();
    ui->radio8Widget->hideMinMax();
647 648 649 650 651 652 653 654 655 656
    ui->radio9Widget->hideMinMax();
    ui->radio10Widget->hideMinMax();
    ui->radio11Widget->hideMinMax();
    ui->radio12Widget->hideMinMax();
    ui->radio13Widget->hideMinMax();
    ui->radio14Widget->hideMinMax();
    ui->radio15Widget->hideMinMax();
    ui->radio16Widget->hideMinMax();
    ui->radio17Widget->hideMinMax();
    ui->radio18Widget->hideMinMax();
657

658 659
    for (unsigned int i = 0; i < chanCount; i++) {
        if (rcMin[i] > 1350) {
660
            rcMin[i] = 1000;
661
        }
662

663
        if (rcMax[i] < 1650) {
664
            rcMax[i] = 2000;
665
        }
666 667
    }

668 669 670
    qDebug() << "SETTING TRIM";
    setTrimPositions();

671 672 673 674 675 676 677 678
    QString statusstr = tr("The calibration has been finished. Please click OK to upload it to the autopilot.");
//    statusstr = tr("This is the RC calibration information that will be sent to the autopilot if you click OK. To prevent transmission, click Cancel.");
//    statusstr += tr("  Normal values range from 1000 to 2000, with disconnected channels reading 1000, 1500, 2000\n\n");
//    statusstr += tr("Channel\tMin\tCenter\tMax\n");
//    statusstr += "-------\t---\t------\t---\n";
//    for (unsigned int i=0; i < chanCount; i++) {
//        statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n";
//    }
679 680 681 682 683

    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();
684 685 686 687

    // Done, exit calibration mode now
    mav->endRadioControlCalibration();

688
    if (QMessageBox::Cancel == msgBoxResult) {
689
        QMessageBox::information(0,"Aborting Calibration","Aborted writing configuration.");
690 691 692 693
        return; //don't commit these values
    } else {
        QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored.");
        writeCalibrationRC();
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
}

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;
721
            tool = new QGCToolWidget("", "", parent);
722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744
            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
745

746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767
     //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;
//            }
//        }
//    }

768 769 770 771

    // Load tabs for general configuration
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
772
        QPushButton *button = new QPushButton(this);
773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795
        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")) {
796
                tool = new QGCToolWidget("", "", tab);
797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815
                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))
    {
816
        QPushButton *button = new QPushButton(this);
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
        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")) {
843
                tool = new QGCToolWidget("", "", tab);
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 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097
                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;
                                }
1098
                                tool = new QGCToolWidget(parametersname, parametersname, parent);
1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149
                                tool->addUAS(mav);
                                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;
                                }
1150
                                tool = new QGCToolWidget(parametersname, parametersname, parent);
1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 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
                                tool->addUAS(mav);
                                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();
    }

1201
    if (!paramTooltips.isEmpty()) {
1202
           paramMgr->setParamDescriptions(paramTooltips);
1203
    }
1204
    doneLoadingConfig = true;
1205
    //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
1206
    paramMgr->requestParameterListIfEmpty();
1207 1208 1209 1210 1211 1212 1213 1214 1215 1216
}

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


tstellanova's avatar
tstellanova committed
1217 1218 1219
    // Do nothing if UAS is already visible
    if (mav == active)
        return;
1220 1221 1222

    if (mav)
    {
1223

1224 1225 1226
        // Disconnect old system
        disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
                   SLOT(remoteControlChannelRawChanged(int,float)));
1227
        //TODO use paramCommsMgr instead
1228 1229 1230 1231
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
                   SLOT(parameterChanged(int,int,QString,QVariant)));

        // Delete all children from all fixed tabs.
1232
        foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>()) {
1233 1234
            child->deleteLater();
        }
1235
        foreach(QWidget* child, ui->generalRightContents->findChildren<QWidget*>()) {
1236 1237
            child->deleteLater();
        }
1238
        foreach(QWidget* child, ui->advanceColumnContents->findChildren<QWidget*>()) {
1239 1240
            child->deleteLater();
        }
1241 1242 1243
//        foreach(QWidget* child, ui->sensorLayout->findChildren<QWidget*>()) {
//            child->deleteLater();
//        }
1244

1245 1246 1247 1248 1249
        foreach(QWidget* child, ui->airframeLayout->findChildren<QWidget*>())
        {
            child->deleteLater();
        }

1250
        // And then delete any custom tabs
1251
        foreach(QWidget* child, additionalTabs) {
1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266
            child->deleteLater();
        }
        additionalTabs.clear();

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

    // Connect new system
    mav = active;

1267 1268
    paramMgr = mav->getParamManager();

tstellanova's avatar
tstellanova committed
1269
    ui->pendingCommitsWidget->setUAS(mav);
1270
    ui->paramTreeWidget->setUAS(mav);
tstellanova's avatar
tstellanova committed
1271

1272 1273
    // Reset current state
    resetCalibrationRC();
1274
    //TODO eliminate the separate RC_TYPE call
1275 1276 1277 1278 1279
    mav->requestParameter(0, "RC_TYPE");

    chanCount = 0;

    // Connect new system
1280
    connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
1281
               SLOT(remoteControlChannelRawChanged(int,float)));
1282
    connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
1283
               SLOT(parameterChanged(int,int,QString,QVariant)));
1284

1285

1286
    if (systemTypeToParamMap.contains(mav->getSystemTypeName())) {
1287 1288
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }
1289
    else {
1290 1291 1292 1293 1294
        //Indication that we have no meta data for this system type.
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }

1295
    if (!paramTooltips.isEmpty()) {
1296
           mav->getParamManager()->setParamDescriptions(paramTooltips);
1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307
    }

    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.
1308 1309 1310 1311 1312
    // Enable buttons
    ui->advancedMenuButton->setEnabled(true);
    ui->airframeMenuButton->setEnabled(true);
    ui->sensorMenuButton->setEnabled(true);
    ui->rcMenuButton->setEnabled(true);
1313 1314 1315

    ui->rcCalibrationButton->setEnabled(true);
    ui->spektrumPairButton->setEnabled(true);
1316 1317 1318 1319
}

void QGCPX4VehicleConfig::resetCalibrationRC()
{
1320
    for (unsigned int i = 0; i < chanMax; ++i) {
1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332
        rcMin[i] = 1500;
        rcMax[i] = 1500;
    }
}

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

1333 1334
    updateStatus(tr("Sending RC configuration and storing to persistent memory."));

1335 1336 1337 1338 1339 1340 1341 1342
    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

1343
    for (unsigned int i = 0; i < chanCount; ++i) {
1344
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
1345 1346 1347 1348
        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);
1349 1350 1351
    }

    // Write mappings
1352 1353 1354 1355 1356
    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));
1357 1358
    paramMgr->setPendingParam(0, "RC_MAP_POSCTL_SW", (int32_t)(rcMapping[5]+1));
    paramMgr->setPendingParam(0, "RC_MAP_LOITER_SW", (int32_t)(rcMapping[6]+1));
1359 1360 1361 1362
    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));
1363 1364

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

1367 1368 1369 1370
}

void QGCPX4VehicleConfig::requestCalibrationRC()
{
1371
    paramMgr->requestRcCalibrationParamsUpdate();
1372 1373 1374 1375 1376 1377 1378 1379
}

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

1380
void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float fval)
1381 1382
{
    // Check if index and values are sane
1383
    if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax || fval < 500.0f || fval > 2500.0f)
1384 1385 1386 1387 1388 1389
        return;

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

1390
    // Raw value
1391
    float deltaRaw = fabsf(fval - rcValue[chan]);
Lorenz Meier's avatar
Lorenz Meier committed
1392
    float delta = fabsf(fval - rcMappedValue[rcToFunctionMapping[chan]]);
1393
    if (!configEnabled && !calibrationEnabled &&
1394 1395
        (deltaRaw < 12.0f && delta < 12.0f && rcValue[chan] > 800 && rcValue[chan] < 2200))
    {
Lorenz Meier's avatar
Lorenz Meier committed
1396
        // ignore tiny jitter values
1397 1398 1399
        return;
    }
    else {
1400
        rcValue[chan] = fval;
1401 1402
    }

1403

1404 1405
    // Update calibration data
    if (calibrationEnabled) {
1406 1407
        if (fval < rcMin[chan]) {
            rcMin[chan] = fval;
1408
        }
1409 1410
        if (fval > rcMax[chan]) {
            rcMax[chan] = fval;
1411 1412 1413
        }
    }

1414 1415
    if (channelWanted >= 0) {
        // If the first channel moved considerably, pick it
1416
        if (fabsf(channelWantedList[chan] - fval) > 300.0f) {
1417
            rcMapping[channelWanted] = chan;
1418
            updateMappingView(channelWanted);
1419 1420 1421 1422

            int chanFound = channelWanted;
            channelWanted = -1;

1423
            // Confirm found channel
1424 1425
            msgBox.setText(tr("Found %1 \t\t").arg(channelNames[chanFound]));
            msgBox.setInformativeText(tr("Assigned raw RC channel %2").arg(chan + 1));
1426 1427
            msgBox.setStandardButtons(QMessageBox::Ok);
            msgBox.setDefaultButton(QMessageBox::Ok);
1428 1429 1430
            skipActionButton->hide();
            msgBox.removeButton(skipActionButton);

1431 1432
            (void)msgBox.exec();

1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450
            // 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:
1451
                ui->posctlSwSpinBox->setValue(chan + 1);
1452 1453
                break;
            case 6:
1454
                ui->loiterSwSpinBox->setValue(chan + 1);
1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468
                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;
            }
1469 1470
        }
    }
1471

1472
    // Reverse raw value
1473 1474
    rcValueReversed[chan] = (rcRev[chan]) ? rcMax[chan] - (fval - rcMin[chan]) : fval;

1475 1476
    // Normalized value
    float normalized;
1477 1478 1479
    float chanTrim = rcTrim[chan];
    if (fval >= rcTrim[chan]) {
        normalized = (fval - chanTrim)/(rcMax[chan] - chanTrim);
1480
    }
1481
    else {
1482
        normalized = -(chanTrim - fval)/(chanTrim - rcMin[chan]);
1483 1484 1485 1486 1487 1488 1489
    }

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

1490
    // Find correct mapped channel
1491
    rcMappedValueRev[rcToFunctionMapping[chan]] = rcValueReversed[chan];
Lorenz Meier's avatar
Lorenz Meier committed
1492
    rcMappedValue[rcToFunctionMapping[chan]] = fval;
1493

Lorenz Meier's avatar
Lorenz Meier committed
1494 1495 1496 1497
    // Copy min / max
    rcMappedMin[rcToFunctionMapping[chan]] = rcMin[chan];
    rcMappedMax[rcToFunctionMapping[chan]] = rcMax[chan];
    rcMappedNormalizedValue[rcToFunctionMapping[chan]] = normalized;
1498

1499
    if (chan == rcMapping[0]) {
1500 1501
        rcRoll = normalized;
    }
1502
    else if (chan == rcMapping[1]) {
1503 1504
        rcPitch = normalized;
    }
1505
    else if (chan == rcMapping[2]) {
1506 1507
        rcYaw = normalized;
    }
1508
    else if (chan == rcMapping[3]) {
1509 1510 1511 1512 1513 1514 1515
        rcThrottle = normalized;
//        if (rcRev[chan]) {
//            rcThrottle = 1.0f + normalized;
//        }
//        else {
//            rcThrottle = normalized;
//        }
1516

1517
//        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
1518
    }
1519
    else if (chan == rcMapping[4]) {
1520
        rcMode = normalized; // MODE SWITCH
1521
    }
1522
    else if (chan == rcMapping[5]) {
1523
        rcAssist = normalized; // ASSIST SWITCH
1524
    }
1525
    else if (chan == rcMapping[6]) {
1526
        rcLoiter = normalized; // LOITER SWITCH
1527
    }
1528
    else if (chan == rcMapping[7]) {
1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557
        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
1558 1559
            msgBox.setText(tr("%1 direction assigned").arg(channelNames[currRevFunc]));
            msgBox.setInformativeText(tr("%1").arg((rcRev[rcMapping[currRevFunc]]) ? tr("Reversed channel.") : tr("Did not reverse channel.") ));
1560 1561
            msgBox.setStandardButtons(QMessageBox::Ok);
            msgBox.setDefaultButton(QMessageBox::Ok);
1562 1563
            skipActionButton->hide();
            msgBox.removeButton(skipActionButton);
1564 1565
            (void)msgBox.exec();
        }
1566 1567
    }

1568
    dataModelChanged = true;
1569

1570
    //qDebug() << "RC CHAN:" << chan << "PPM:" << fval << "NORMALIZED:" << normalized;
1571 1572
}

1573
void QGCPX4VehicleConfig::updateAllInvertedCheckboxes()
1574
{
1575
    for (unsigned function_index = 0; function_index < chanMappedMax; function_index++) {
1576

1577 1578
        int rc_input_index = rcMapping[function_index];

Lorenz Meier's avatar
Lorenz Meier committed
1579
        if (rc_input_index < 0 || rc_input_index > (int)chanMax)
1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606
            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:
1607
            ui->posctlSwInvertCheckBox->setChecked(rcRev[rc_input_index]);
1608 1609
            break;
        case 6:
1610
            ui->loiterSwInvertCheckBox->setChecked(rcRev[rc_input_index]);
1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663
            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;
1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693
        case 8:
            ui->radio9Widget->setName(tr("%1 (#9)").arg(assignments[8]));
            break;
        case 9:
            ui->radio10Widget->setName(tr("%1 (#10)").arg(assignments[9]));
            break;
        case 10:
            ui->radio11Widget->setName(tr("%1 (#11)").arg(assignments[10]));
            break;
        case 11:
            ui->radio12Widget->setName(tr("%1 (#12)").arg(assignments[11]));
            break;
        case 12:
            ui->radio13Widget->setName(tr("%1 (#13)").arg(assignments[12]));
            break;
        case 13:
            ui->radio14Widget->setName(tr("%1 (#14)").arg(assignments[13]));
            break;
        case 14:
            ui->radio15Widget->setName(tr("%1 (#15)").arg(assignments[14]));
            break;
        case 15:
            ui->radio16Widget->setName(tr("%1 (#16)").arg(assignments[15]));
            break;
        case 16:
            ui->radio17Widget->setName(tr("%1 (#17)").arg(assignments[16]));
            break;
        case 17:
            ui->radio18Widget->setName(tr("%1 (#18)").arg(assignments[17]));
            break;
1694
        }
1695 1696 1697
    }
}

1698 1699 1700 1701 1702 1703 1704 1705
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;
1706

1707
            if (parameterName.startsWith("RC_MAP_ROLL")) {
1708
                setChannelToFunctionMapping(0, intValue);
1709 1710 1711 1712
                ui->rollSpinBox->setValue(rcMapping[0]+1);
                ui->rollSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_PITCH")) {
1713
                setChannelToFunctionMapping(1, intValue);
1714 1715 1716 1717
                ui->pitchSpinBox->setValue(rcMapping[1]+1);
                ui->pitchSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_YAW")) {
1718
                setChannelToFunctionMapping(2, intValue);
1719 1720 1721 1722
                ui->yawSpinBox->setValue(rcMapping[2]+1);
                ui->yawSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_THROTTLE")) {
1723
                setChannelToFunctionMapping(3, intValue);
1724 1725 1726 1727
                ui->throttleSpinBox->setValue(rcMapping[3]+1);
                ui->throttleSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_MODE_SW")) {
1728
                setChannelToFunctionMapping(4, intValue);
1729 1730 1731
                ui->modeSpinBox->setValue(rcMapping[4]+1);
                ui->modeSpinBox->setEnabled(true);
            }
1732
            else if (parameterName.startsWith("RC_MAP_POSCTL_SW")) {
1733
                setChannelToFunctionMapping(5, intValue);
1734 1735
                ui->posctlSwSpinBox->setValue(rcMapping[5]+1);
                ui->posctlSwSpinBox->setEnabled(true);
1736
            }
1737
            else if (parameterName.startsWith("RC_MAP_LOITER_SW")) {
1738
                setChannelToFunctionMapping(6, intValue);
1739 1740
                ui->loiterSwSpinBox->setValue(rcMapping[6]+1);
                ui->loiterSwSpinBox->setEnabled(true);
1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751
            }
            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);
            }
1752
            else if (parameterName.startsWith("RC_MAP_AUX1")) {
1753 1754
                setChannelToFunctionMapping(9, intValue);
                ui->aux1SpinBox->setValue(rcMapping[9]+1);
1755 1756 1757
                ui->aux1SpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_AUX2")) {
1758 1759
                setChannelToFunctionMapping(10, intValue);
                ui->aux2SpinBox->setValue(rcMapping[10]+1);
1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774
                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;
            }
1775 1776 1777 1778 1779 1780 1781 1782 1783 1784
            // 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;
//            }
1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827
        }
    }
    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;
1828 1829 1830 1831 1832 1833

                for (unsigned i = 0; i < chanMappedMax; i++)
                {
                    if (rcMapping[i] == (int)index)
                        updateMappingView(i);
                }
1834 1835 1836
            }
        }
    }
1837
}
1838

1839 1840 1841 1842 1843 1844 1845
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;
1846 1847
}

1848 1849
void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
1850
    if (!doneLoadingConfig) {
1851 1852 1853 1854 1855
        //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;
    }

1856
    //TODO this may introduce a bug with param editor widgets not receiving param updates
1857 1858 1859 1860 1861 1862
    if (parameterName.startsWith("RC")) {
        handleRcParameterChange(parameterName,value);
        return;
    }

    if (paramToWidgetMap.contains(parameterName)) {
1863 1864
        //Main group of parameters of the selected airframe
        paramToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
1865
        if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName))) {
1866 1867
            toolToBoxMap[paramToWidgetMap.value(parameterName)]->show();
        }
1868
        else {
1869 1870 1871
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
        }
    }
1872
    else if (libParamToWidgetMap.contains(parameterName)) {
1873 1874
        //All the library parameters
        libParamToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
1875
        if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName))) {
1876 1877
            toolToBoxMap[libParamToWidgetMap.value(parameterName)]->show();
        }
1878
        else {
1879 1880 1881
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
        }
    }
1882
    else {
1883 1884
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
1885
        //bool found = false;
1886 1887
        for (int i=0;i<toolWidgets.size();i++) {
            if (parameterName.startsWith(toolWidgets[i]->objectName())) {
1888 1889 1890
                //It should be grouped with this one, add it.
                toolWidgets[i]->addParam(uas,component,parameterName,value);
                libParamToWidgetMap.insert(parameterName,toolWidgets[i]);
1891
                //found  = true;
1892 1893 1894
                break;
            }
        }
1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921
//        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;
//        }
1922 1923 1924 1925 1926 1927
    }

}

void QGCPX4VehicleConfig::updateStatus(const QString& str)
{
1928 1929
    ui->advancedStatusLabel->setText(str);
    ui->advancedStatusLabel->setStyleSheet("");
1930 1931 1932 1933
}

void QGCPX4VehicleConfig::updateError(const QString& str)
{
1934 1935
    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()));
1936
}
1937

1938 1939
void QGCPX4VehicleConfig::checktimeOuts()
{
1940

1941 1942
}

1943 1944 1945

void QGCPX4VehicleConfig::updateRcWidgetValues()
{
1946 1947 1948 1949
    ui->rollWidget->setValueAndRange(rcMappedValueRev[0],rcMappedMin[0],rcMappedMax[0]);
    ui->pitchWidget->setValueAndRange(rcMappedValueRev[1],rcMappedMin[1],rcMappedMax[1]);
    ui->yawWidget->setValueAndRange(rcMappedValueRev[2],rcMappedMin[2],rcMappedMax[2]);
    ui->throttleWidget->setValueAndRange(rcMappedValueRev[3],rcMappedMin[3],rcMappedMax[3]);
1950

1951 1952 1953 1954
    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]);
1955 1956 1957 1958 1959 1960 1961 1962 1963 1964
    ui->radio9Widget->setValueAndRange(rcValueReversed[8],rcMin[8],rcMax[8]);
    ui->radio10Widget->setValueAndRange(rcValueReversed[9],rcMin[9],rcMax[9]);
    ui->radio11Widget->setValueAndRange(rcValueReversed[10],rcMin[10],rcMax[10]);
    ui->radio12Widget->setValueAndRange(rcValueReversed[11],rcMin[11],rcMax[11]);
    ui->radio13Widget->setValueAndRange(rcValueReversed[12],rcMin[12],rcMax[12]);
    ui->radio14Widget->setValueAndRange(rcValueReversed[13],rcMin[13],rcMax[13]);
    ui->radio15Widget->setValueAndRange(rcValueReversed[14],rcMin[14],rcMax[14]);
    ui->radio16Widget->setValueAndRange(rcValueReversed[15],rcMin[15],rcMax[15]);
    ui->radio17Widget->setValueAndRange(rcValueReversed[16],rcMin[16],rcMax[16]);
    ui->radio18Widget->setValueAndRange(rcValueReversed[17],rcMin[17],rcMax[17]);
1965 1966
}

1967
void QGCPX4VehicleConfig::updateRcChanLabels()
1968
{
1969 1970 1971 1972 1973 1974
    ui->rollChanLabel->setText(labelForRcValue(rcRoll));
    ui->pitchChanLabel->setText(labelForRcValue(rcPitch));
    ui->yawChanLabel->setText(labelForRcValue(rcYaw));
    ui->throttleChanLabel->setText(labelForRcValue(rcThrottle));

    QString blankLabel = tr("---");
1975
    if (rcValue[rcMapping[4]] != UINT16_MAX) {
1976 1977 1978 1979 1980
        ui->modeChanLabel->setText(labelForRcValue(rcMode));
    }
    else {
        ui->modeChanLabel->setText(blankLabel);
    }
1981

1982
    if (rcValue[rcMapping[5]] != UINT16_MAX) {
1983
        ui->posctlSwChanLabel->setText(labelForRcValue(rcAssist));
1984 1985
    }
    else {
1986
        ui->posctlSwChanLabel->setText(blankLabel);
1987
    }
1988

1989
    if (rcValue[rcMapping[6]] != UINT16_MAX) {
1990
        ui->loiterSwChanLabel->setText(labelForRcValue(rcLoiter));
1991 1992
    }
    else {
1993
        ui->loiterSwChanLabel->setText(blankLabel);
1994
    }
1995

1996
    if (rcValue[rcMapping[7]] != UINT16_MAX) {
1997 1998 1999 2000 2001 2002 2003 2004
        ui->returnSwChanLabel->setText(labelForRcValue(rcReturn));
    }
    else {
        ui->returnSwChanLabel->setText(blankLabel);
    }

    if (rcValue[rcMapping[8]] != UINT16_MAX) {
        ui->flapsChanLabel->setText(labelForRcValue(rcFlaps));
2005 2006
    }
    else {
2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021
        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);
2022 2023
    }
}
2024

2025 2026 2027 2028
void QGCPX4VehicleConfig::updateView()
{
    if (dataModelChanged) {
        dataModelChanged = false;
2029

2030 2031
        updateRcWidgetValues();
        updateRcChanLabels();
Lorenz Meier's avatar
Lorenz Meier committed
2032 2033
        if (chanCount > 0)
            ui->rcLabel->setText(tr("Radio control detected with %1 channels.").arg(chanCount));
2034
    }
Lorenz Meier's avatar
Lorenz Meier committed
2035

2036
}