QGCPX4VehicleConfig.cc 62.2 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
#include "QGC.h"
19
#include "QGCPendingParamWidget.h"
20
#include "QGCToolWidget.h"
21 22
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
23
#include "ui_QGCPX4VehicleConfig.h"
24
#include "px4_configuration/QGCPX4AirframeConfig.h"
25
#include <dialog_bare.h>
tstellanova's avatar
tstellanova committed
26

27 28 29 30 31 32
#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
33 34 35 36

#define MIN_PWM_VAL 800
#define MAX_PWM_VAL 2200

37 38 39 40 41 42 43 44 45 46 47 48
QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
    QWidget(parent),
    mav(NULL),
    chanCount(0),
    rcRoll(0.0f),
    rcPitch(0.0f),
    rcYaw(0.0f),
    rcThrottle(0.0f),
    rcMode(0.0f),
    rcAux1(0.0f),
    rcAux2(0.0f),
    rcAux3(0.0f),
49
    dataModelChanged(true),
50
    channelWanted(-1),
51 52
    rc_mode(RC_MODE_NONE),
    calibrationEnabled(false),
53
    px4AirframeConfig(NULL),
54 55 56
    #ifdef QUPGRADE_SUPPORT
    firmwareDialog(NULL),
    #endif
57 58 59 60
    ui(new Ui::QGCPX4VehicleConfig)
{
    doneLoadingConfig = false;

61 62 63 64 65 66 67 68 69 70 71 72 73
    channelNames << "Roll / Aileron";
    channelNames << "Pitch / Elevator";
    channelNames << "Yaw / Rudder";
    channelNames << "Throttle";
    channelNames << "SW1 / Main Mode Switch";
    channelNames << "SW2 / Sub Mode Switch";
    channelNames << "Aux1 / Flaps";
    channelNames << "Aux2";
    channelNames << "Aux3";
    channelNames << "Aux4";
    channelNames << "Aux5";
    channelNames << "Aux6";

74 75 76
    setObjectName("QGC_VEHICLECONFIG");
    ui->setupUi(this);

77 78 79
    px4AirframeConfig = new QGCPX4AirframeConfig(this);
    ui->airframeLayout->addWidget(px4AirframeConfig);

80 81 82 83 84 85 86 87 88 89 90
#ifdef QUPGRADE_SUPPORT
    firmwareDialog = new DialogBare(this);
    ui->firmwareLayout->addWidget(firmwareDialog);
#else
#error Please check out QUpgrade from http://github.com/LorenzMeier/qupgrade/ into the QGroundControl folder.

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

91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109
    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");

    connect(ui->rcMenuButton,SIGNAL(clicked()),this,SLOT(rcMenuButtonClicked()));
    connect(ui->sensorMenuButton,SIGNAL(clicked()),this,SLOT(sensorMenuButtonClicked()));
    connect(ui->generalMenuButton,SIGNAL(clicked()),this,SLOT(generalMenuButtonClicked()));
    connect(ui->advancedMenuButton,SIGNAL(clicked()),this,SLOT(advancedMenuButtonClicked()));
110
    connect(ui->airframeMenuButton, SIGNAL(clicked()), this, SLOT(airframeMenuButtonClicked()));
111
    connect(ui->firmwareMenuButton, SIGNAL(clicked()), this, SLOT(firmwareButtonClicked()));
112 113 114

    ui->rcCalibrationButton->setCheckable(true);
    connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
115 116 117
    connect(ui->writeButton, SIGNAL(clicked()),
            this, SLOT(writeParameters()));

118
    //TODO connect buttons here to save/clear actions?
119 120 121
    UASInterface* tmpMav = UASManager::instance()->getActiveUAS();
    if (tmpMav) {
        ui->pendingCommitsWidget->initWithUAS(tmpMav);
tstellanova's avatar
tstellanova committed
122
        ui->pendingCommitsWidget->update();
123
        setActiveUAS(tmpMav);
tstellanova's avatar
tstellanova committed
124
    }
125

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

129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156
    // Connect RC mapping assignments
    connect(ui->rollSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setRollChan(int)));
    connect(ui->pitchSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setPitchChan(int)));
    connect(ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYawChan(int)));
    connect(ui->throttleSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setThrottleChan(int)));
    connect(ui->modeSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setModeChan(int)));
    connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int)));
    connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(int)));
    connect(ui->aux3SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux3Chan(int)));

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

    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()));
    connect(ui->subButton, SIGNAL(clicked()), this, SLOT(identifySubModeChannel()));
    connect(ui->aux1Button, SIGNAL(clicked()), this, SLOT(identifyAux1Channel()));
    connect(ui->aux2Button, SIGNAL(clicked()), this, SLOT(identifyAux2Channel()));
157

158
    for (unsigned int i = 0; i < chanMax; i++) {
159 160
        rcValue[i] = UINT16_MAX;
        rcMapping[i] = i;
161 162 163
        channelWantedList[i] = UINT16_MAX;
        rcMin[i] = 1000;
        rcMax[i] = 2000;
164 165 166 167 168 169
    }

    updateTimer.setInterval(150);
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
    updateTimer.start();
}
170

171 172
void QGCPX4VehicleConfig::rcMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
173 174
    //TODO eg ui->stackedWidget->findChild("rcConfig");
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_RC);
175 176 177 178
}

void QGCPX4VehicleConfig::sensorMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
179
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_SENSOR_CAL);
180 181 182 183
}

void QGCPX4VehicleConfig::generalMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
184
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_GENERAL_CONFIG);
185 186 187 188
}

void QGCPX4VehicleConfig::advancedMenuButtonClicked()
{
tstellanova's avatar
tstellanova committed
189
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_ADV_CONFIG);
190 191
}

192 193 194 195 196
void QGCPX4VehicleConfig::airframeMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_AIRFRAME_CONFIG);
}

197 198 199 200 201
void QGCPX4VehicleConfig::firmwareMenuButtonClicked()
{
    ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_FIRMWARE);
}

202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218
void QGCPX4VehicleConfig::identifyChannelMapping(int aert_index)
{
    if (chanCount == 0)
        return;
    channelWanted = aert_index;

    for (unsigned i = 0; i < sizeof(channelWantedList) / sizeof(channelWantedList[0]); i++)
    {
        if (i >= chanCount) {
            channelWantedList[i] = 0;
        } else {
            channelWantedList[i] = rcValue[i];
        }
    }

}

219 220 221 222 223 224 225
QGCPX4VehicleConfig::~QGCPX4VehicleConfig()
{
    delete ui;
}

void QGCPX4VehicleConfig::setRCModeIndex(int newRcMode)
{
226 227 228 229
    newRcMode += 1; //promote from an index to a mode enum
    if (newRcMode > 0 && newRcMode < 5) {
        rc_mode = (enum RC_MODE) (newRcMode);
        dataModelChanged = true;
230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305
    }
}

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

void QGCPX4VehicleConfig::setTrimPositions()
{
    // Set trim to min if stick is close to min
    if (abs(rcValue[rcMapping[3]] - rcMin[rcMapping[3]]) < 100)
    {
        rcTrim[rcMapping[3]] = rcMin[rcMapping[3]];   // throttle
    }
    // Set trim to max if stick is close to max
    else if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100)
    {
        rcTrim[rcMapping[3]] = rcMax[rcMapping[3]];   // throttle
    }
    else
    {
        // Reject
        QMessageBox msgBox;
        msgBox.setText(tr("Throttle Stick Trim Position Invalid"));
        msgBox.setInformativeText(tr("The throttle stick is not in the min position. Please set it to the minimum value"));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        (void)msgBox.exec();
    }

    // Set trim for roll, pitch, yaw, throttle
    rcTrim[rcMapping[0]] = rcValue[rcMapping[0]]; // roll
    rcTrim[rcMapping[1]] = rcValue[rcMapping[1]]; // pitch
    rcTrim[rcMapping[2]] = rcValue[rcMapping[2]]; // yaw

    rcTrim[rcMapping[4]] = ((rcMax[rcMapping[4]] - rcMin[rcMapping[4]]) / 2.0f) + rcMin[rcMapping[4]];   // mode sw
    rcTrim[rcMapping[5]] = ((rcMax[rcMapping[5]] - rcMin[rcMapping[5]]) / 2.0f) + rcMin[rcMapping[5]];   // aux 1
    rcTrim[rcMapping[6]] = ((rcMax[rcMapping[6]] - rcMin[rcMapping[6]]) / 2.0f) + rcMin[rcMapping[6]];   // aux 2
    rcTrim[rcMapping[7]] = ((rcMax[rcMapping[7]] - rcMin[rcMapping[7]]) / 2.0f) + rcMin[rcMapping[7]];   // aux 3
}

void QGCPX4VehicleConfig::detectChannelInversion()
{

}

void QGCPX4VehicleConfig::startCalibrationRC()
{
    QMessageBox::information(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and reciever are powered and connected\n\nClick OK to confirm");
    QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
    ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
    resetCalibrationRC();
    calibrationEnabled = true;
    ui->rollWidget->showMinMax();
    ui->pitchWidget->showMinMax();
    ui->yawWidget->showMinMax();
    ui->throttleWidget->showMinMax();
    ui->radio5Widget->showMinMax();
    ui->radio6Widget->showMinMax();
    ui->radio7Widget->showMinMax();
    ui->radio8Widget->showMinMax();
}

void QGCPX4VehicleConfig::stopCalibrationRC()
{
    QMessageBox::information(0,"Trims","Ensure all sticks are centeres and throttle is in the downmost position, click OK to continue");
    calibrationEnabled = false;
    ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
306

307 308 309 310 311 312 313 314
    ui->rollWidget->hideMinMax();
    ui->pitchWidget->hideMinMax();
    ui->yawWidget->hideMinMax();
    ui->throttleWidget->hideMinMax();
    ui->radio5Widget->hideMinMax();
    ui->radio6Widget->hideMinMax();
    ui->radio7Widget->hideMinMax();
    ui->radio8Widget->hideMinMax();
315

316 317 318 319 320 321 322 323 324
    for (int i=0;i<chanCount;i++)
    {
        if (rcMin[i] > 1350)
            rcMin[i] = 1000;

        if (rcMax[i] < 1650)
            rcMax[i] = 2000;
    }

325 326
    QString statusstr;
    statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n";
327
    statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading 1000, 1500, 2000\n\n";
328 329
    statusstr += "Channel\tMin\tCenter\tMax\n";
    statusstr += "--------------------\n";
330
    for (int i=0;i<chanCount;i++)
331
    {
332
        statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n";
333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388
    }
    QMessageBox::information(0,"Status",statusstr);
}

void QGCPX4VehicleConfig::loadQgcConfig(bool primary)
{
    Q_UNUSED(primary);
    QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower());
    QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets");
    QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets");
    if (!autopilotdir.exists("general"))
    {
     //TODO: Throw some kind of error here. There is no general configuration directory
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
    }

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

    // Generate widgets for the Advanced tab.
    foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
    {
        if (file.toLower().endsWith(".qgw")) {
tstellanova's avatar
tstellanova committed
389
            QWidget* parent = ui->advanceColumnContents;
390 391 392 393 394 395 396 397
            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);
tstellanova's avatar
tstellanova committed
398 399
                ui->advancedColumnLayout->addWidget(box);

400 401 402 403 404 405 406 407 408
            } else {
                delete tool;
            }
        }
    }

    // Load tabs for general configuration
    foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
409
        QPushButton *button = new QPushButton(ui->leftNavScrollAreaWidgetContents);
410 411 412 413 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 443 444 445 446 447 448 449 450 451 452
        connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
        ui->navBarLayout->insertWidget(2,button);
        button->setMinimumHeight(75);
        button->setMinimumWidth(100);
        button->show();
        button->setText(dir);
        QWidget *tab = new QWidget(ui->stackedWidget);
        ui->stackedWidget->insertWidget(2,tab);
        buttonToWidgetMap[button] = tab;
        tab->setLayout(new QVBoxLayout());
        tab->show();
        QScrollArea *area = new QScrollArea(tab);
        tab->layout()->addWidget(area);
        QWidget *scrollArea = new QWidget(tab);
        scrollArea->setLayout(new QVBoxLayout(tab));
        area->setWidget(scrollArea);
        area->setWidgetResizable(true);
        area->show();
        scrollArea->show();
        QDir newdir = QDir(generaldir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", tab);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
                    QGroupBox *box = new QGroupBox(tab);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout(tab));
                    box->layout()->addWidget(tool);
                    scrollArea->layout()->addWidget(box);
                } else {
                    delete tool;
                }
            }
        }
    }

    // Load additional tabs for vehicle specific configuration
    foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
    {
453
        QPushButton *button = new QPushButton(ui->leftNavScrollAreaWidgetContents);
454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499
        connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
        ui->navBarLayout->insertWidget(2,button);

        QWidget *tab = new QWidget(ui->stackedWidget);
        ui->stackedWidget->insertWidget(2,tab);
        buttonToWidgetMap[button] = tab;

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

        QDir newdir = QDir(vehicledir.absoluteFilePath(dir));
        foreach (QString file,newdir.entryList(QDir::Files| QDir::NoDotAndDotDot))
        {
            if (file.toLower().endsWith(".qgw")) {
                tool = new QGCToolWidget("", tab);
                tool->addUAS(mav);
                if (tool->loadSettings(newdir.absoluteFilePath(file), false))
                {
                    toolWidgets.append(tool);
                    //ui->sensorLayout->addWidget(tool);
                    QGroupBox *box = new QGroupBox(tab);
                    box->setTitle(tool->objectName());
                    box->setLayout(new QVBoxLayout(box));
                    box->layout()->addWidget(tool);
                    scrollArea->layout()->addWidget(box);
                    box->show();
                    //gbox->layout()->addWidget(box);
                } else {
                    delete tool;
                }
            }
        }
    }

500

501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531
    // Load general calibration for autopilot
    //TODO: Handle this more gracefully, maybe have it scan the directory for multiple calibration entries?
    tool = new QGCToolWidget("", ui->sensorContents);
    tool->addUAS(mav);
    if (tool->loadSettings(autopilotdir.absolutePath() + "/general/calibration/calibration.qgw", false))
    {
        toolWidgets.append(tool);
        QGroupBox *box = new QGroupBox(ui->sensorContents);
        box->setTitle(tool->objectName());
        box->setLayout(new QVBoxLayout(box));
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
    } else {
        delete tool;
    }

    // Load vehicle-specific autopilot configuration
    tool = new QGCToolWidget("", ui->sensorContents);
    tool->addUAS(mav);
    if (tool->loadSettings(autopilotdir.absolutePath() + "/" +  mav->getSystemTypeName().toLower() + "/calibration/calibration.qgw", false))
    {
        toolWidgets.append(tool);
        QGroupBox *box = new QGroupBox(ui->sensorContents);
        box->setTitle(tool->objectName());
        box->setLayout(new QVBoxLayout(box));
        box->layout()->addWidget(tool);
        ui->sensorLayout->addWidget(box);
    } else {
        delete tool;
    }

532 533 534 535 536
//    //description.txt
//    QFile sensortipsfile(autopilotdir.absolutePath() + "/general/calibration/description.txt");
//    sensortipsfile.open(QIODevice::ReadOnly);
////    ui->sensorTips->setHtml(sensortipsfile.readAll());
//    sensortipsfile.close();
537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879
}
void QGCPX4VehicleConfig::menuButtonClicked()
{
    QPushButton *button = qobject_cast<QPushButton*>(sender());
    if (!button)
    {
        return;
    }
    if (buttonToWidgetMap.contains(button))
    {
        ui->stackedWidget->setCurrentWidget(buttonToWidgetMap[button]);
    }

}

void QGCPX4VehicleConfig::loadConfig()
{
    QGCToolWidget* tool;

    QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower());
    QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets");
    QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets");
    if (!autopilotdir.exists("general"))
    {
     //TODO: Throw some kind of error here. There is no general configuration directory
        qWarning() << "Invalid general dir. no general configuration will be loaded.";
    }
    if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
    {
        //TODO: Throw an error here too, no autopilot specific configuration
        qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded.";
    }
    qDebug() << autopilotdir.absolutePath();
    qDebug() << generaldir.absolutePath();
    qDebug() << vehicledir.absolutePath();
    QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
    if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
    {
        loadQgcConfig(false);
        doneLoadingConfig = true;
        return;
    }
    loadQgcConfig(true);

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

    //TODO: Testing to ensure that incorrectly formatted XML won't break this.
    while (!xml.atEnd())
    {
        if (xml.isStartElement() && xml.name() == "paramfile")
        {
            xml.readNext();
            while ((xml.name() != "paramfile") && !xml.atEnd())
            {
                QString valuetype = "";
                if (xml.isStartElement() && (xml.name() == "vehicles" || xml.name() == "libraries")) //Enter into the vehicles loop
                {
                    valuetype = xml.name().toString();
                    xml.readNext();
                    while ((xml.name() != valuetype) && !xml.atEnd())
                    {
                        if (xml.isStartElement() && xml.name() == "parameters") //This is a parameter block
                        {
                            QString parametersname = "";
                            if (xml.attributes().hasAttribute("name"))
                            {
                                    parametersname = xml.attributes().value("name").toString();
                            }
                            QVariantMap genset;
                            QVariantMap advset;

                            QString setname = parametersname;
                            xml.readNext();
                            int genarraycount = 0;
                            int advarraycount = 0;
                            while ((xml.name() != "parameters") && !xml.atEnd())
                            {
                                if (xml.isStartElement() && xml.name() == "param")
                                {
                                    QString humanname = xml.attributes().value("humanName").toString();
                                    QString name = xml.attributes().value("name").toString();
                                    QString tab= xml.attributes().value("user").toString();
                                    if (tab == "Advanced")
                                    {
                                        advset["title"] = parametersname;
                                    }
                                    else
                                    {
                                        genset["title"] = parametersname;
                                    }
                                    if (name.contains(":"))
                                    {
                                        name = name.split(":")[1];
                                    }
                                    QString docs = xml.attributes().value("documentation").toString();
                                    paramTooltips[name] = name + " - " + docs;

                                    int type = -1; //Type of item
                                    QMap<QString,QString> fieldmap;
                                    xml.readNext();
                                    while ((xml.name() != "param") && !xml.atEnd())
                                    {
                                        if (xml.isStartElement() && xml.name() == "values")
                                        {
                                            type = 1; //1 is a combobox
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "COMBO";
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "COMBO";
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
                                            }
                                            int paramcount = 0;
                                            xml.readNext();
                                            while ((xml.name() != "values") && !xml.atEnd())
                                            {
                                                if (xml.isStartElement() && xml.name() == "value")
                                                {

                                                    QString code = xml.attributes().value("code").toString();
                                                    QString arg = xml.readElementText();
                                                    if (tab == "Advanced")
                                                    {
                                                        advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
                                                        advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
                                                    }
                                                    else
                                                    {
                                                        genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
                                                        genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
                                                    }
                                                    paramcount++;
                                                }
                                                xml.readNext();
                                            }
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
                                            }
                                        }
                                        if (xml.isStartElement() && xml.name() == "field")
                                        {
                                            type = 2; //2 is a slider
                                            QString fieldtype = xml.attributes().value("name").toString();
                                            QString text = xml.readElementText();
                                            fieldmap[fieldtype] = text;
                                        }
                                        xml.readNext();
                                    }
                                    if (type == -1)
                                    {
                                        //Nothing inside! Assume it's a value, give it a default range.
                                        type = 2;
                                        QString fieldtype = "Range";
                                        QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
                                        fieldmap[fieldtype] = text;
                                    }
                                    if (type == 2)
                                    {
                                        if (tab == "Advanced")
                                        {
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "SLIDER";
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
                                            advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
                                        }
                                        else
                                        {
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "SLIDER";
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
                                            genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
                                        }
                                        if (fieldmap.contains("Range"))
                                        {
                                            float min = 0;
                                            float max = 0;
                                            //Some range fields list "0-10" and some list "0 10". Handle both.
                                            if (fieldmap["Range"].split(" ").size() > 1)
                                            {
                                                min = fieldmap["Range"].split(" ")[0].trimmed().toFloat();
                                                max = fieldmap["Range"].split(" ")[1].trimmed().toFloat();
                                            }
                                            else if (fieldmap["Range"].split("-").size() > 1)
                                            {
                                                min = fieldmap["Range"].split("-")[0].trimmed().toFloat();
                                                max = fieldmap["Range"].split("-")[1].trimmed().toFloat();
                                            }
                                            if (tab == "Advanced")
                                            {
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
                                                advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
                                            }
                                            else
                                            {
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
                                                genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
                                            }
                                        }
                                    }
                                    if (tab == "Advanced")
                                    {
                                        advarraycount++;
                                        advset["count"] = advarraycount;
                                    }
                                    else
                                    {
                                        genarraycount++;
                                        genset["count"] = genarraycount;
                                    }
                                }
                                xml.readNext();
                            }
                            if (genarraycount > 0)
                            {
                                QWidget* parent = this;
                                if (valuetype == "vehicles")
                                {
                                    parent = ui->generalLeftContents;
                                }
                                else if (valuetype == "libraries")
                                {
                                    parent = ui->generalRightContents;
                                }
                                tool = new QGCToolWidget("", parent);
                                tool->addUAS(mav);
                                tool->setTitle(parametersname);
                                tool->setObjectName(parametersname);
                                tool->setSettings(genset);
                                QList<QString> paramlist = tool->getParamList();
                                for (int i=0;i<paramlist.size();i++)
                                {
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
                                        systemTypeToParamMap["FIXED_WING"].insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
                                        systemTypeToParamMap["QUADROTOR"].insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
                                        systemTypeToParamMap["GROUND_ROVER"].insert(paramlist[i],tool);
                                    }
                                    else
                                    {
                                        libParamToWidgetMap.insert(paramlist[i],tool);
                                    }
                                }

                                toolWidgets.append(tool);
                                QGroupBox *box = new QGroupBox(parent);
                                box->setTitle(tool->objectName());
                                box->setLayout(new QVBoxLayout(box));
                                box->layout()->addWidget(tool);
                                if (valuetype == "vehicles")
                                {
                                    ui->generalLeftLayout->addWidget(box);
                                }
                                else if (valuetype == "libraries")
                                {
                                    ui->generalRightLayout->addWidget(box);
                                }
                                box->hide();
                                toolToBoxMap[tool] = box;
                            }
                            if (advarraycount > 0)
                            {
                                QWidget* parent = this;
                                if (valuetype == "vehicles")
                                {
                                    parent = ui->generalLeftContents;
                                }
                                else if (valuetype == "libraries")
                                {
                                    parent = ui->generalRightContents;
                                }
                                tool = new QGCToolWidget("", parent);
                                tool->addUAS(mav);
                                tool->setTitle(parametersname);
                                tool->setObjectName(parametersname);
                                tool->setSettings(advset);
                                QList<QString> paramlist = tool->getParamList();
                                for (int i=0;i<paramlist.size();i++)
                                {
                                    //Based on the airframe, we add the parameter to different categories.
                                    if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
                                    {
                                        systemTypeToParamMap["FIXED_WING"].insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
                                    {
                                        systemTypeToParamMap["QUADROTOR"].insert(paramlist[i],tool);
                                    }
                                    else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
                                    {
                                        systemTypeToParamMap["GROUND_ROVER"].insert(paramlist[i],tool);
                                    }
                                    else
                                    {
                                        libParamToWidgetMap.insert(paramlist[i],tool);
                                    }
                                }

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

880
    if (!paramTooltips.isEmpty()) {
881
           paramMgr->setParamDescriptions(paramTooltips);
882
    }
883
    doneLoadingConfig = true;
884
    //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
885
    paramMgr->requestParameterListIfEmpty();
886 887 888 889 890 891 892
}

void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
{
    // Hide items if NULL and abort
    if (!active) {
        ui->refreshButton->setEnabled(false);
893
        ui->refreshButton->show();
894
        ui->readButton->setEnabled(false);
895
        ui->readButton->show();
896
        ui->writeButton->setEnabled(false);
897
        ui->writeButton->show();
898
        ui->loadFileButton->setEnabled(false);
899
        ui->loadFileButton->show();
900
        ui->saveFileButton->setEnabled(false);
901
        ui->saveFileButton->show();
902 903 904 905 906

        return;
    }


tstellanova's avatar
tstellanova committed
907 908 909
    // Do nothing if UAS is already visible
    if (mav == active)
        return;
910 911 912

    if (mav)
    {
913

914 915 916
        // Disconnect old system
        disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
                   SLOT(remoteControlChannelRawChanged(int,float)));
917
        //TODO use paramCommsMgr instead
918 919
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
                   SLOT(parameterChanged(int,int,QString,QVariant)));
920
        disconnect(ui->refreshButton,SIGNAL(clicked()),
921
                   paramMgr,SLOT(requestParameterList()));
922 923

        // Delete all children from all fixed tabs.
924
        foreach(QWidget* child, ui->generalLeftContents->findChildren<QWidget*>()) {
925 926
            child->deleteLater();
        }
927
        foreach(QWidget* child, ui->generalRightContents->findChildren<QWidget*>()) {
928 929
            child->deleteLater();
        }
930
        foreach(QWidget* child, ui->advanceColumnContents->findChildren<QWidget*>()) {
931 932
            child->deleteLater();
        }
933
        foreach(QWidget* child, ui->sensorContents->findChildren<QWidget*>()) {
934 935 936
            child->deleteLater();
        }

937 938 939 940 941
        foreach(QWidget* child, ui->airframeLayout->findChildren<QWidget*>())
        {
            child->deleteLater();
        }

942
        // And then delete any custom tabs
943
        foreach(QWidget* child, additionalTabs) {
944 945 946 947 948 949 950 951 952 953 954 955 956 957 958
            child->deleteLater();
        }
        additionalTabs.clear();

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

    // Connect new system
    mav = active;

959 960
    paramMgr = mav->getParamManager();

tstellanova's avatar
tstellanova committed
961 962
    ui->pendingCommitsWidget->setUAS(mav);

963 964
    // Reset current state
    resetCalibrationRC();
965
    //TODO eliminate the separate RC_TYPE call
966 967 968 969
    mav->requestParameter(0, "RC_TYPE");

    chanCount = 0;

970
    //TODO get parameter changes via Param Mgr instead
971
    // Connect new system
972
    connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
973
               SLOT(remoteControlChannelRawChanged(int,float)));
974
    connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
975
               SLOT(parameterChanged(int,int,QString,QVariant)));
976
    connect(ui->refreshButton, SIGNAL(clicked()),
977
            paramMgr,SLOT(requestParameterList()));
978

979
    if (systemTypeToParamMap.contains(mav->getSystemTypeName())) {
980 981
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }
982
    else {
983 984 985 986 987
        //Indication that we have no meta data for this system type.
        qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
        paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
    }

988
    if (!paramTooltips.isEmpty()) {
989
           mav->getParamManager()->setParamDescriptions(paramTooltips);
990 991 992 993 994 995 996 997 998 999 1000 1001
    }

    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.
    ui->refreshButton->setEnabled(true);
1002
    ui->refreshButton->show();
1003
    ui->readButton->setEnabled(true);
1004
    ui->readButton->show();
1005
    ui->writeButton->setEnabled(true);
1006
    ui->writeButton->show();
1007
    ui->loadFileButton->setEnabled(true);
1008
    ui->loadFileButton->show();
1009
    ui->saveFileButton->setEnabled(true);
1010 1011 1012
    ui->saveFileButton->show();

    //TODO never true?
1013
    if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA") {
1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034
        ui->readButton->hide();
        ui->writeButton->hide();
    }
}

void QGCPX4VehicleConfig::resetCalibrationRC()
{
    for (unsigned int i = 0; i < chanMax; ++i)
    {
        rcMin[i] = 1500;
        rcMax[i] = 1500;
    }
}

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

1035 1036
    setTrimPositions();

1037 1038 1039 1040 1041 1042 1043 1044
    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

1045
    //TODO consolidate RC param sending in the UAS comms mgr
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
    for (unsigned int i = 0; i < chanCount; ++i)
    {
        //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
        mav->setParameter(0, minTpl.arg(i+1), rcMin[i]);
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]);
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
        QGC::SLEEP::usleep(50000);
        mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
        QGC::SLEEP::usleep(50000);
    }

    // Write mappings
    mav->setParameter(0, "RC_MAP_ROLL", (int32_t)(rcMapping[0]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_PITCH", (int32_t)(rcMapping[1]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_MODE_SW", (int32_t)(rcMapping[4]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_AUX1", (int32_t)(rcMapping[5]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_AUX2", (int32_t)(rcMapping[6]+1));
    QGC::SLEEP::usleep(50000);
    mav->setParameter(0, "RC_MAP_AUX3", (int32_t)(rcMapping[7]+1));
    QGC::SLEEP::usleep(50000);
}

void QGCPX4VehicleConfig::requestCalibrationRC()
{
1080
    paramMgr->requestRcCalibrationParamsUpdate();
1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099
}

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

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

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

1100 1101 1102
    // Raw value
    rcValue[chan] = val;

1103 1104
    // Update calibration data
    if (calibrationEnabled) {
1105
        if (val < rcMin[chan]) {
1106 1107
            rcMin[chan] = val;
        }
1108
        if (val > rcMax[chan]) {
1109 1110 1111 1112
            rcMax[chan] = val;
        }
    }

1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123
    if (channelWanted >= 0) {
        // If the first channel moved considerably, pick it
        if (fabsf(channelWantedList[chan] - val) > 300)
        {
            rcMapping[channelWanted] = chan;
            updateInvertedCheckboxes(chan);

            int chanFound = channelWanted;

            channelWanted = -1;

1124
            // Confirm found channel
1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146
            QMessageBox msgBox;
            msgBox.setText(tr("%1 Channel found.").arg(channelNames[chanFound]));
            msgBox.setInformativeText(tr("Found %1 to be on the raw RC channel %2").arg(channelNames[chanFound]).arg(chan + 1));
            msgBox.setStandardButtons(QMessageBox::Ok);
            msgBox.setDefaultButton(QMessageBox::Ok);
            (void)msgBox.exec();
        }
    }

    // Find correct mapped channel
    for (int i = 0; i < chanCount; i++)
    {
        if (chan == rcMapping[i])
        {

            rcMappedValue[i] = (rcRev[chan]) ? rcMax[chan] - (val - rcMin[chan]) : val;

            // Copy min / max
            rcMappedMin[i] = rcMin[chan];
            rcMappedMax[i] = rcMax[chan];
        }
    }
1147 1148 1149 1150

    // Normalized value
    float normalized;

1151
    if (val >= rcTrim[chan]) {
1152 1153
        normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
    }
1154
    else {
1155 1156 1157 1158 1159 1160 1161 1162
        normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]);
    }

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

1163
    if (chan == rcMapping[0]) {
1164 1165
        rcRoll = normalized;
    }
1166
    else if (chan == rcMapping[1]) {
1167 1168
        rcPitch = normalized;
    }
1169
    else if (chan == rcMapping[2]) {
1170 1171
        rcYaw = normalized;
    }
1172
    else if (chan == rcMapping[3]) {
1173 1174 1175 1176 1177 1178 1179 1180
        if (rcRev[chan]) {
            rcThrottle = 1.0f + normalized;
        } else {
            rcThrottle = normalized;
        }

        rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
    }
1181 1182
    else if (chan == rcMapping[4]) {
        rcMode = normalized;// MODE SWITCH
1183
    }
1184 1185
    else if (chan == rcMapping[5]) {
        rcAux1 = normalized; // AUX1
1186
    }
1187 1188
    else if (chan == rcMapping[6]) {
        rcAux2 = normalized;// AUX2
1189
    }
1190 1191
    else if (chan == rcMapping[7]) {
        rcAux3 = normalized; // AUX3
1192 1193
    }

1194
    dataModelChanged = true;
1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231

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

void QGCPX4VehicleConfig::updateInvertedCheckboxes(int index)
{
    unsigned int mapindex = rcMapping[index];

    switch (mapindex)
    {
    case 0:
        ui->invertCheckBox->setChecked(rcRev[index]);
        break;
    case 1:
        ui->invertCheckBox_2->setChecked(rcRev[index]);
        break;
    case 2:
        ui->invertCheckBox_3->setChecked(rcRev[index]);
        break;
    case 3:
        ui->invertCheckBox_4->setChecked(rcRev[index]);
        break;
    case 4:
        ui->invertCheckBox_5->setChecked(rcRev[index]);
        break;
    case 5:
        ui->invertCheckBox_6->setChecked(rcRev[index]);
        break;
    case 6:
        ui->invertCheckBox_7->setChecked(rcRev[index]);
        break;
    case 7:
        ui->invertCheckBox_8->setChecked(rcRev[index]);
        break;
    }
}

1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366
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;
            if (parameterName.startsWith("RC_MAP_ROLL")) {
                rcMapping[0] = intValue;
                ui->rollSpinBox->setValue(rcMapping[0]+1);
                ui->rollSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_PITCH")) {
                rcMapping[1] = intValue;
                ui->pitchSpinBox->setValue(rcMapping[1]+1);
                ui->pitchSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_YAW")) {
                rcMapping[2] = intValue;
                ui->yawSpinBox->setValue(rcMapping[2]+1);
                ui->yawSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_THROTTLE")) {
                rcMapping[3] = intValue;
                ui->throttleSpinBox->setValue(rcMapping[3]+1);
                ui->throttleSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_MODE_SW")) {
                rcMapping[4] = intValue;
                ui->modeSpinBox->setValue(rcMapping[4]+1);
                ui->modeSpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_AUX1")) {
                rcMapping[5] = intValue;
                ui->aux1SpinBox->setValue(rcMapping[5]+1);
                ui->aux1SpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_AUX2")) {
                rcMapping[6] = intValue;
                ui->aux2SpinBox->setValue(rcMapping[6]+1);
                ui->aux2SpinBox->setEnabled(true);
            }
            else if (parameterName.startsWith("RC_MAP_AUX3")) {
                rcMapping[7] = intValue;
                ui->aux3SpinBox->setValue(rcMapping[7]+1);
                ui->aux3SpinBox->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;
            }
            else if (parameterName.startsWith("RC_SCALE_THROTTLE")) {
                rcScaling[3] = floatVal;
            }
            else if (parameterName.startsWith("RC_SCALE_MODE_SW")) {
                rcScaling[4] = floatVal;
            }
            else if (parameterName.startsWith("RC_SCALE_AUX1")) {
                rcScaling[5] = floatVal;
            }
            else if (parameterName.startsWith("RC_SCALE_AUX2")) {
                rcScaling[6] = floatVal;
            }
            else if (parameterName.startsWith("RC_SCALE_AUX3")) {
                rcScaling[7] = floatVal;
            }
        }
        else if (parameterName.startsWith("RC_TYPE")) {
            if (0 != rcTypeUpdateRequested) {
                rcTypeUpdateRequested = 0;
                updateStatus(tr("Received RC type update, setting parameters based on model."));
                rcType = value.toInt();
                // Request all other parameters as well
                requestCalibrationRC();
            }
        }
    }
    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;
                updateInvertedCheckboxes(index);
            }
        }
    }

}

1367 1368
void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
1369
    if (!doneLoadingConfig) {
1370 1371 1372 1373 1374
        //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;
    }

1375
    //TODO this may introduce a bug with param editor widgets not receiving param updates
1376 1377 1378 1379 1380 1381
    if (parameterName.startsWith("RC")) {
        handleRcParameterChange(parameterName,value);
        return;
    }

    if (paramToWidgetMap.contains(parameterName)) {
1382 1383
        //Main group of parameters of the selected airframe
        paramToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
1384
        if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName))) {
1385 1386
            toolToBoxMap[paramToWidgetMap.value(parameterName)]->show();
        }
1387
        else {
1388 1389 1390
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
        }
    }
1391
    else if (libParamToWidgetMap.contains(parameterName)) {
1392 1393
        //All the library parameters
        libParamToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value);
1394
        if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName))) {
1395 1396
            toolToBoxMap[libParamToWidgetMap.value(parameterName)]->show();
        }
1397
        else {
1398 1399 1400
            qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName;
        }
    }
1401
    else {
1402 1403 1404
        //Param recieved that we have no metadata for. Search to see if it belongs in a
        //group with some other params
        bool found = false;
1405 1406
        for (int i=0;i<toolWidgets.size();i++) {
            if (parameterName.startsWith(toolWidgets[i]->objectName())) {
1407 1408 1409 1410 1411 1412 1413
                //It should be grouped with this one, add it.
                toolWidgets[i]->addParam(uas,component,parameterName,value);
                libParamToWidgetMap.insert(parameterName,toolWidgets[i]);
                found  = true;
                break;
            }
        }
1414
        if (!found) {
1415
            //New param type, create a QGroupBox for it.
tstellanova's avatar
tstellanova committed
1416
            QWidget* parent = ui->advanceColumnContents;
1417 1418 1419 1420

            // Create the tool, attaching it to the QGroupBox
            QGCToolWidget *tool = new QGCToolWidget("", parent);
            QString tooltitle = parameterName;
1421
            if (parameterName.split("_").size() > 1) {
1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436
                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);
tstellanova's avatar
tstellanova committed
1437
            ui->advancedColumnLayout->addWidget(box);
1438 1439 1440 1441 1442 1443 1444 1445 1446

            toolToBoxMap[tool] = box;
        }
    }

}

void QGCPX4VehicleConfig::updateStatus(const QString& str)
{
1447 1448
    ui->advancedStatusLabel->setText(str);
    ui->advancedStatusLabel->setStyleSheet("");
1449 1450 1451 1452
}

void QGCPX4VehicleConfig::updateError(const QString& str)
{
1453 1454
    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()));
1455
}
1456

1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479

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

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

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

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

1480 1481 1482

void QGCPX4VehicleConfig::updateRcWidgetValues()
{
1483 1484 1485 1486 1487 1488 1489 1490 1491
    ui->rollWidget->setValueAndRange(rcMappedValue[0],rcMappedMin[0],rcMappedMax[0]);
    ui->pitchWidget->setValueAndRange(rcMappedValue[1],rcMappedMin[1],rcMappedMax[1]);
    ui->yawWidget->setValueAndRange(rcMappedValue[2],rcMappedMin[2],rcMappedMax[2]);
    ui->throttleWidget->setValueAndRange(rcMappedValue[3],rcMappedMin[3],rcMappedMax[3]);

    ui->radio5Widget->setValueAndRange(rcMappedValue[4],rcMin[4],rcMax[4]);
    ui->radio6Widget->setValueAndRange(rcMappedValue[5],rcMin[5],rcMax[5]);
    ui->radio7Widget->setValueAndRange(rcMappedValue[6],rcMin[6],rcMax[6]);
    ui->radio8Widget->setValueAndRange(rcMappedValue[7],rcMin[7],rcMax[7]);
1492 1493
}

1494 1495
void QGCPX4VehicleConfig::updateView()
{
1496 1497 1498
    if (dataModelChanged) {
        dataModelChanged = false;

1499
        updateRcWidgetValues();
1500

1501
        //update the channel labels
1502 1503 1504 1505
        ui->rollChanLabel->setText(QString("%1").arg(rcRoll, 5, 'f', 2, QChar(' ')));
        ui->pitchChanLabel->setText(QString("%1").arg(rcPitch, 5, 'f', 2, QChar(' ')));
        ui->yawChanLabel->setText(QString("%1").arg(rcYaw, 5, 'f', 2, QChar(' ')));
        ui->throttleChanLabel->setText(QString("%1").arg(rcThrottle, 5, 'f', 2, QChar(' ')));
1506 1507

        if (rcValue[rcMapping[4] != UINT16_MAX]) {
1508
            ui->modeChanLabel->setText(QString("%1").arg(rcMode, 5, 'f', 2, QChar(' ')));
1509
        } else {
1510
            ui->modeChanLabel->setText(tr("---"));
1511 1512 1513
        }

        if (rcValue[rcMapping[5]] != UINT16_MAX) {
1514
            ui->aux1ChanLabel->setText(QString("%1").arg(rcAux1, 5, 'f', 2, QChar(' ')));
1515
        } else {
1516
            ui->aux1ChanLabel->setText(tr("---"));
1517 1518 1519
        }

        if (rcValue[rcMapping[6]] != UINT16_MAX) {
1520
            ui->aux2ChanLabel->setText(QString("%1").arg(rcAux2, 5, 'f', 2, QChar(' ')));
1521
        } else {
1522
            ui->aux2ChanLabel->setText(tr("---"));
1523 1524 1525
        }

        if (rcValue[rcMapping[7]] != UINT16_MAX) {
1526
            ui->aux3ChanLabel->setText(QString("%1").arg(rcAux3, 5, 'f', 2, QChar(' ')));
1527
        } else {
1528
            ui->aux3ChanLabel->setText(tr("---"));
1529 1530 1531 1532
        }

    }
}