QGCPX4AirframeConfig.cc 15.6 KB
Newer Older
1
#include <QMessageBox>
2
#include <QProgressDialog>
3
#include <QDebug>
4
#include <QTimer>
5

Lorenz Meier's avatar
Lorenz Meier committed
6 7 8
#include "QGCPX4AirframeConfig.h"
#include "ui_QGCPX4AirframeConfig.h"

9
#include "UASManager.h"
10
#include "LinkManager.h"
11
#include "UAS.h"
12
#include "QGC.h"
13

Lorenz Meier's avatar
Lorenz Meier committed
14 15
QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) :
    QWidget(parent),
16
    mav(NULL),
17 18 19
    progress(NULL),
    pendingParams(0),
    configState(CONFIG_STATE_ABORT),
20
    selectedId(-1),
Lorenz Meier's avatar
Lorenz Meier committed
21 22 23
    ui(new Ui::QGCPX4AirframeConfig)
{
    ui->setupUi(this);
24 25 26 27

    // Fill the lists here manually in accordance with the list from:
    // https://github.com/PX4/Firmware/blob/master/ROMFS/px4fmu_common/init.d/rcS

28 29
    ui->planeComboBox->addItem(tr("Multiplex Easystar 1/2"), 100);
    ui->planeComboBox->addItem(tr("Hobbyking Bixler 1/2"), 101);
30

31
    connect(ui->planePushButton, SIGNAL(clicked()), this, SLOT(planeSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
32
    connect(ui->planeComboBox, SIGNAL(activated(int)), this, SLOT(planeSelected(int)));
Lorenz Meier's avatar
Lorenz Meier committed
33
    ui->planePushButton->setEnabled(ui->planeComboBox->count() > 0);
34

35 36
    ui->flyingWingComboBox->addItem(tr("Bormatec Camflyer Q"), 30);
    ui->flyingWingComboBox->addItem(tr("Phantom FPV"), 31);
37

38
    connect(ui->flyingWingPushButton, SIGNAL(clicked()), this, SLOT(flyingWingSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
39
    connect(ui->flyingWingComboBox, SIGNAL(activated(int)), this, SLOT(flyingWingSelected(int)));
40 41

    ui->quadXComboBox->addItem(tr("DJI F330 8\" Quad"), 10);
Lorenz Meier's avatar
Lorenz Meier committed
42
    ui->quadXComboBox->addItem(tr("DJI F450 10\" Quad"), 11);
43
    ui->quadXComboBox->addItem(tr("Turnigy Talon v2 X550 Quad"), 666);
Lorenz Meier's avatar
Lorenz Meier committed
44 45
    ui->quadXComboBox->addItem(tr("AR.Drone Frame Quad"), 8);
    ui->quadXComboBox->addItem(tr("AR.Drone Quad (w. PX4FLOW)"), 9);
46

47
    connect(ui->quadXPushButton, SIGNAL(clicked()), this, SLOT(quadXSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
48
    connect(ui->quadXComboBox, SIGNAL(activated(int)), this, SLOT(quadXSelected(int)));
49

50
    connect(ui->quadPlusPushButton, SIGNAL(clicked()), this, SLOT(quadPlusSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
51
    connect(ui->quadPlusComboBox, SIGNAL(activated(int)), this, SLOT(quadPlusSelected(int)));
Lorenz Meier's avatar
Lorenz Meier committed
52
    ui->quadPlusPushButton->setEnabled(ui->quadPlusComboBox->count() > 0);
53

Lorenz Meier's avatar
Lorenz Meier committed
54
    connect(ui->hexaXPushButton, SIGNAL(clicked()), this, SLOT(hexaXSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
55
    connect(ui->hexaXComboBox, SIGNAL(activated(int)), this, SLOT(hexaXSelected(int)));
Lorenz Meier's avatar
Lorenz Meier committed
56
    ui->hexaXPushButton->setEnabled(ui->hexaXComboBox->count() > 0);
57

Lorenz Meier's avatar
Lorenz Meier committed
58
    connect(ui->hexaPlusPushButton, SIGNAL(clicked()), this, SLOT(hexaPlusSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
59
    connect(ui->hexaPlusComboBox, SIGNAL(activated(int)), this, SLOT(hexaPlusSelected(int)));
Lorenz Meier's avatar
Lorenz Meier committed
60
    ui->hexaPlusPushButton->setEnabled(ui->hexaPlusComboBox->count() > 0);
61

Lorenz Meier's avatar
Lorenz Meier committed
62
    connect(ui->octoXPushButton, SIGNAL(clicked()), this, SLOT(octoXSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
63
    connect(ui->octoXComboBox, SIGNAL(activated(int)), this, SLOT(octoXSelected(int)));
Lorenz Meier's avatar
Lorenz Meier committed
64
    ui->octoXPushButton->setEnabled(ui->octoXComboBox->count() > 0);
65

Lorenz Meier's avatar
Lorenz Meier committed
66
    connect(ui->octoPlusPushButton, SIGNAL(clicked()), this, SLOT(octoPlusSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
67
    connect(ui->octoPlusComboBox, SIGNAL(activated(int)), this, SLOT(octoPlusSelected(int)));
Lorenz Meier's avatar
Lorenz Meier committed
68
    ui->octoPlusPushButton->setEnabled(ui->octoPlusComboBox->count() > 0);
69

Lorenz Meier's avatar
Lorenz Meier committed
70
    ui->hComboBox->addItem(tr("3DR Iris"), 16);
71 72
    ui->hComboBox->addItem(tr("TBS Discovery"), 15);

Lorenz Meier's avatar
Lorenz Meier committed
73 74 75 76
    connect(ui->hPushButton, SIGNAL(clicked()), this, SLOT(hSelected()));
    connect(ui->hComboBox, SIGNAL(activated(int)), this, SLOT(hSelected(int)));
    ui->hPushButton->setEnabled(ui->hComboBox->count() > 0);

77 78
    connect(ui->applyButton, SIGNAL(clicked()), this, SLOT(applyAndReboot()));

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

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

    uncheckAll();
84 85
}

Lorenz Meier's avatar
Lorenz Meier committed
86 87 88 89 90 91 92 93 94 95 96 97
void QGCPX4AirframeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);

    if (parameterName.contains("SYS_AUTOSTART"))
    {
        int index = value.toInt();
        if (index > 0) {
            setAirframeID(index);
            ui->statusLabel->setText(tr("Onboard start script ID: #%1").arg(index));
        } else {
98
            uncheckAll();
Lorenz Meier's avatar
Lorenz Meier committed
99 100 101 102 103
            ui->statusLabel->setText(tr("System not configured for autostart."));
        }
    }
}

104 105
void QGCPX4AirframeConfig::setActiveUAS(UASInterface* uas)
{
Lorenz Meier's avatar
Lorenz Meier committed
106 107 108
    if (mav)
    {
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
109
        mav = NULL;
Lorenz Meier's avatar
Lorenz Meier committed
110
    }
111 112 113 114 115

    if (!uas)
        return;

    mav = uas;
116
    paramMgr = mav->getParamManager();
117

Lorenz Meier's avatar
Lorenz Meier committed
118
    connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
119
}
Lorenz Meier's avatar
Lorenz Meier committed
120

121 122 123 124 125 126 127 128 129 130 131
void QGCPX4AirframeConfig::uncheckAll()
{
    ui->planePushButton->setChecked(false);
    ui->flyingWingPushButton->setChecked(false);
    ui->quadXPushButton->setChecked(false);
    ui->quadPlusPushButton->setChecked(false);
    ui->hexaXPushButton->setChecked(false);
    ui->hexaPlusPushButton->setChecked(false);
    ui->octoXPushButton->setChecked(false);
    ui->octoPlusPushButton->setChecked(false);
    ui->hPushButton->setChecked(false);
132 133 134 135
}

void QGCPX4AirframeConfig::setAirframeID(int id)
{
136 137 138 139

    qDebug() << "setAirframeID" << id;
    ui->statusLabel->setText(tr("Start script ID: #%1").arg(id));

140
    selectedId = id;
Lorenz Meier's avatar
Lorenz Meier committed
141

142 143 144 145 146 147
    // XXX too much boilerplate code here - this widget is really just
    // a quick hack to get started
    uncheckAll();

    if (id > 0 && id < 15) {
        ui->quadXPushButton->setChecked(true);
148
        ui->quadXComboBox->setCurrentIndex(ui->quadXComboBox->findData(id));
149
        ui->statusLabel->setText(tr("Selected quad X (ID: #%1)").arg(selectedId));
Lorenz Meier's avatar
Lorenz Meier committed
150
    }
151
    else if (id >= 15 && id < 20)
Lorenz Meier's avatar
Lorenz Meier committed
152
    {
153
        ui->hPushButton->setChecked(true);
154 155
        ui->hComboBox->setCurrentIndex(ui->hComboBox->findData(id));
        ui->statusLabel->setText(tr("Selected H Frame (ID: #%1)").arg(selectedId));
156 157 158 159
    }
    else if (id >= 30 && id < 50)
    {
        ui->flyingWingPushButton->setChecked(true);
160
        ui->flyingWingComboBox->setCurrentIndex(ui->flyingWingComboBox->findData(id));
161
        ui->statusLabel->setText(tr("Selected flying wing (ID: #%1)").arg(selectedId));
162 163 164 165
    }
    else if (id >= 100 && id < 150)
    {
        ui->planePushButton->setChecked(true);
166
        ui->planeComboBox->setCurrentIndex(ui->planeComboBox->findData(id));
167
        ui->statusLabel->setText(tr("Selected plane (ID: #%1)").arg(selectedId));
Lorenz Meier's avatar
Lorenz Meier committed
168
    }
169 170 171 172
}

void QGCPX4AirframeConfig::applyAndReboot()
{
173
    // Guard against the case of an edit where we didn't receive all params yet
Lorenz Meier's avatar
Lorenz Meier committed
174
    if (selectedId <= 0)
175 176 177 178 179 180 181 182 183 184 185 186 187 188
    {
        QMessageBox msgBox;
        msgBox.setText(tr("No airframe selected"));
        msgBox.setInformativeText(tr("Please select an airframe first."));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        (void)msgBox.exec();

        return;
    }

    if (!mav)
        return;

189 190
    if (paramMgr->countOnboardParams() == 0 &&
            paramMgr->countPendingParams() == 0)
191
    {
192 193
        paramMgr->requestParameterList();
        QGC::SLEEP::msleep(300);
194 195
    }

196 197
    QList<int> components = paramMgr->getComponentForParam("SYS_AUTOSTART");

198
    // Guard against the case of an edit where we didn't receive all params yet
199
    if (paramMgr->countPendingParams() > 0 || components.count() == 0)
200 201 202 203 204 205 206
    {
        QMessageBox msgBox;
        msgBox.setText(tr("Parameter sync with UAS not yet complete"));
        msgBox.setInformativeText(tr("Please wait a few moments and retry"));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        (void)msgBox.exec();
207 208

        return;
209 210 211 212 213 214 215 216 217 218 219 220 221 222
    }

    // Guard against multiple components responding - this will never show in practice
    if (components.count() != 1) {
        QMessageBox msgBox;
        msgBox.setText(tr("Invalid system setup detected"));
        msgBox.setInformativeText(tr("None or more than one component advertised to provide the main system configuration option. This is an invalid system setup - please check your autopilot."));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        (void)msgBox.exec();

        return;
    }

223 224 225 226 227 228 229 230 231 232 233 234 235 236
    // This is really evil: 'fake' a thread by
    // periodic work queue calls and clock
    // through a small state machine
    // ugh.. if we just had time to do this properly.

    // To the reader who can't program and wants to whine:
    // this is not beautiful, but technically completely
    // sound. If you want to fix it, you'd be welcome
    // to rebase the link, param manager and UI classes
    // on a proper threading framework - which I'd love to do
    // if I just had more time..

    configState = CONFIG_STATE_SEND;
    QTimer::singleShot(200, this, SLOT(checkConfigState()));
Lorenz Meier's avatar
Lorenz Meier committed
237
    setEnabled(false);
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
}

void QGCPX4AirframeConfig::checkConfigState()
{

    if (configState == CONFIG_STATE_SEND)
    {
        QList<int> components = paramMgr->getComponentForParam("SYS_AUTOSTART");
        qDebug() << "Setting comp" << components.first() << "SYS_AUTOSTART" << (qint32)selectedId;

        paramMgr->setPendingParam(components.first(),"SYS_AUTOSTART", (qint32)selectedId);

        //need to set autoconfig in order for PX4 to pick up the selected airframe params
        if (ui->defaultGainsCheckBox->checkState() == Qt::Checked)
                setAutoConfig(true);

        // Send pending params and then write them to persistent storage when done
        paramMgr->sendPendingParameters(true);

        configState = CONFIG_STATE_WAIT_PENDING;
        pendingParams = 0;
        QTimer::singleShot(2000, this, SLOT(checkConfigState()));
        return;
    }

    if (configState == CONFIG_STATE_WAIT_PENDING) {
        // Guard against the case of an edit where we didn't receive all params yet
        if (paramMgr->countPendingParams() > 0)
        {
            if (pendingParams == 0) {

                pendingParams = paramMgr->countPendingParams();

                if (progress)
                    delete progress;

                progress = new QProgressDialog("Writing parameters", "Abort Send", 0, pendingParams, this);
                progress->setWindowModality(Qt::WindowModal);
                progress->setMinimumDuration(2000);
            }

            qDebug() << "PENDING" << paramMgr->countPendingParams() << "PROGRESS" << pendingParams - paramMgr->countPendingParams();
            progress->setValue(pendingParams - paramMgr->countPendingParams());

            if (progress->wasCanceled()) {
                configState = CONFIG_STATE_ABORT;
Lorenz Meier's avatar
Lorenz Meier committed
284
                setEnabled(true);
285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315
                pendingParams = 0;
                return;
            }
        } else {
            pendingParams = 0;
            configState = CONFIG_STATE_REBOOT;
        }

        qDebug() << "PENDING PARAMS WAIT PENDING: " << paramMgr->countPendingParams();
        QTimer::singleShot(1000, this, SLOT(checkConfigState()));
        return;
    }

    if (configState == CONFIG_STATE_REBOOT) {

        // Reboot
        //TODO right now this relies upon the above send & persist finishing before the reboot command is received...

        unsigned pendingMax = 20;

        qDebug() << "PENDING PARAMS REBOOT BEFORE" << pendingParams;

        if (pendingParams == 0) {
            pendingParams = 1;

            if (progress)
                delete progress;

            progress = new QProgressDialog("Waiting for autopilot reboot", "Abort", 0, pendingMax, this);
            progress->setWindowModality(Qt::WindowModal);
            qDebug() << "Waiting for reboot, pending" << pendingParams;
Lorenz Meier's avatar
Lorenz Meier committed
316 317 318 319 320 321 322
        } else {
            if (progress->wasCanceled()) {
                configState = CONFIG_STATE_ABORT;
                setEnabled(true);
                pendingParams = 0;
                return;
            }
323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356
        }

        if (pendingParams == 3) {
            qDebug() << "REQUESTING REBOOT";
            mav->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
            mav->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
        }

        if (pendingParams == 4) {
            qDebug() << "DISCONNECT AIRFRAME";
            LinkManager::instance()->disconnectAll();
        }

        if (pendingParams == 14) {
            qDebug() << "CONNECT AIRFRAME";
            LinkManager::instance()->connectAll();
        }
        if (pendingParams == 15) {
            qDebug() << "DISCONNECT AIRFRAME";
            LinkManager::instance()->disconnectAll();
        }
        if (pendingParams == 16) {
            qDebug() << "CONNECT AIRFRAME";
            LinkManager::instance()->connectAll();
        }

        if (pendingParams < pendingMax) {
            progress->setValue(pendingParams);
            QTimer::singleShot(1000, this, SLOT(checkConfigState()));
        } else {
            paramMgr->requestParameterList();
            progress->setValue(pendingMax);
            configState = CONFIG_STATE_ABORT;
            pendingParams = 0;
Lorenz Meier's avatar
Lorenz Meier committed
357
            setEnabled(true);
358 359 360 361 362 363
            return;
        }
        qDebug() << "PENDING PARAMS REBOOT AFTER:" << pendingParams;
        pendingParams++;
        return;
    }
364 365 366 367 368 369
}

void QGCPX4AirframeConfig::setAutoConfig(bool enabled)
{
    if (!mav)
        return;
370
    paramMgr->setPendingParam(0, "SYS_AUTOCONFIG", (qint32) ((enabled) ? 1 : 0));
371 372 373 374
}

void QGCPX4AirframeConfig::flyingWingSelected()
{
375
    flyingWingSelected(ui->flyingWingComboBox->currentIndex());
Lorenz Meier's avatar
Lorenz Meier committed
376 377
}

378 379 380 381 382 383 384 385
void QGCPX4AirframeConfig::flyingWingSelected(int index)
{
    int system_index = ui->flyingWingComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::planeSelected()
{
386
    planeSelected(ui->planeComboBox->currentIndex());
387 388 389 390 391 392 393 394 395 396 397
}

void QGCPX4AirframeConfig::planeSelected(int index)
{
    int system_index = ui->planeComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}


void QGCPX4AirframeConfig::quadXSelected()
{
398
    quadXSelected(ui->quadXComboBox->currentIndex());
399 400 401 402 403 404 405 406 407 408
}

void QGCPX4AirframeConfig::quadXSelected(int index)
{
    int system_index = ui->quadXComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::quadPlusSelected()
{
409
    quadPlusSelected(ui->quadPlusComboBox->currentIndex());
410 411 412 413 414 415 416 417 418 419
}

void QGCPX4AirframeConfig::quadPlusSelected(int index)
{
    int system_index = ui->quadPlusComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::hexaXSelected()
{
420
    hexaXSelected(ui->hexaXComboBox->currentIndex());
421 422 423 424 425 426 427 428 429 430
}

void QGCPX4AirframeConfig::hexaXSelected(int index)
{
    int system_index = ui->hexaXComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::hexaPlusSelected()
{
431
    hexaPlusSelected(ui->hexaPlusComboBox->currentIndex());
432 433 434 435 436 437 438 439 440 441
}

void QGCPX4AirframeConfig::hexaPlusSelected(int index)
{
    int system_index = ui->hexaPlusComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::octoXSelected()
{
442
    octoXSelected(ui->octoXComboBox->currentIndex());
443 444 445 446 447 448 449 450 451 452
}

void QGCPX4AirframeConfig::octoXSelected(int index)
{
    int system_index = ui->octoXComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::octoPlusSelected()
{
453
    octoPlusSelected(ui->octoPlusComboBox->currentIndex());
454 455 456 457 458 459 460 461 462 463
}

void QGCPX4AirframeConfig::octoPlusSelected(int index)
{
    int system_index = ui->octoPlusComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::hSelected()
{
464
    hSelected(ui->hComboBox->currentIndex());
465 466 467 468 469 470 471 472 473
}

void QGCPX4AirframeConfig::hSelected(int index)
{
    int system_index = ui->hComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}


Lorenz Meier's avatar
Lorenz Meier committed
474 475 476 477
QGCPX4AirframeConfig::~QGCPX4AirframeConfig()
{
    delete ui;
}