QGCPX4AirframeConfig.cc 14.3 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)));
33

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

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

    ui->quadXComboBox->addItem(tr("Standard 10\" Quad"), 1);
    ui->quadXComboBox->addItem(tr("DJI F330 8\" Quad"), 10);
42
    ui->quadXComboBox->addItem(tr("Turnigy Talon v2 X550 Quad"), 666);
43

44
    connect(ui->quadXPushButton, SIGNAL(clicked()), this, SLOT(quadXSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
45
    connect(ui->quadXComboBox, SIGNAL(activated(int)), this, SLOT(quadXSelected(int)));
46

47
    connect(ui->quadPlusPushButton, SIGNAL(clicked()), this, SLOT(quadPlusSelected()));
Lorenz Meier's avatar
Lorenz Meier committed
48
    connect(ui->quadPlusComboBox, SIGNAL(activated(int)), this, SLOT(quadPlusSelected(int)));
49

Lorenz Meier's avatar
Lorenz Meier committed
50
    connect(ui->hexaXComboBox, SIGNAL(activated(int)), this, SLOT(hexaXSelected(int)));
51

Lorenz Meier's avatar
Lorenz Meier committed
52
    connect(ui->hexaPlusComboBox, SIGNAL(activated(int)), this, SLOT(hexaPlusSelected(int)));
53

Lorenz Meier's avatar
Lorenz Meier committed
54
    connect(ui->octoXComboBox, SIGNAL(activated(int)), this, SLOT(octoXSelected(int)));
55

Lorenz Meier's avatar
Lorenz Meier committed
56
    connect(ui->octoPlusComboBox, SIGNAL(activated(int)), this, SLOT(octoPlusSelected(int)));
57

Lorenz Meier's avatar
Lorenz Meier committed
58
    connect(ui->hComboBox, SIGNAL(activated(int)), this, SLOT(hSelected(int)));
59

60 61 62
    ui->hComboBox->addItem(tr("TBS Discovery"), 15);
    ui->hComboBox->addItem(tr("H Custom"), 16);

63 64
    connect(ui->applyButton, SIGNAL(clicked()), this, SLOT(applyAndReboot()));

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

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

    uncheckAll();
70 71
}

Lorenz Meier's avatar
Lorenz Meier committed
72 73 74 75 76 77 78 79 80 81 82 83
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 {
84
            uncheckAll();
Lorenz Meier's avatar
Lorenz Meier committed
85 86 87 88 89
            ui->statusLabel->setText(tr("System not configured for autostart."));
        }
    }
}

90 91
void QGCPX4AirframeConfig::setActiveUAS(UASInterface* uas)
{
Lorenz Meier's avatar
Lorenz Meier committed
92 93 94
    if (mav)
    {
        disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
95
        mav = NULL;
Lorenz Meier's avatar
Lorenz Meier committed
96
    }
97 98 99 100 101

    if (!uas)
        return;

    mav = uas;
102
    paramMgr = mav->getParamManager();
103

Lorenz Meier's avatar
Lorenz Meier committed
104
    connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
105
}
Lorenz Meier's avatar
Lorenz Meier committed
106

107 108 109 110 111 112 113 114 115 116 117
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);
118 119 120 121
}

void QGCPX4AirframeConfig::setAirframeID(int id)
{
122 123 124 125 126 127 128

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

    if (selectedId == id)
        return;

129
    selectedId = id;
Lorenz Meier's avatar
Lorenz Meier committed
130

131 132 133 134 135 136
    // 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);
137
        ui->quadXComboBox->setCurrentIndex(ui->quadXComboBox->findData(id));
138
        ui->statusLabel->setText(tr("Selected quad X (ID: #%1)").arg(selectedId));
Lorenz Meier's avatar
Lorenz Meier committed
139
    }
140
    else if (id >= 15 && id < 20)
Lorenz Meier's avatar
Lorenz Meier committed
141
    {
142
        ui->hPushButton->setChecked(true);
143 144
        ui->hComboBox->setCurrentIndex(ui->hComboBox->findData(id));
        ui->statusLabel->setText(tr("Selected H Frame (ID: #%1)").arg(selectedId));
145 146 147 148
    }
    else if (id >= 30 && id < 50)
    {
        ui->flyingWingPushButton->setChecked(true);
149
        ui->flyingWingComboBox->setCurrentIndex(ui->flyingWingComboBox->findData(id));
150
        ui->statusLabel->setText(tr("Selected flying wing (ID: #%1)").arg(selectedId));
151 152 153 154
    }
    else if (id >= 100 && id < 150)
    {
        ui->planePushButton->setChecked(true);
155
        ui->planeComboBox->setCurrentIndex(ui->planeComboBox->findData(id));
156
        ui->statusLabel->setText(tr("Selected plane (ID: #%1)").arg(selectedId));
Lorenz Meier's avatar
Lorenz Meier committed
157
    }
158 159 160 161
}

void QGCPX4AirframeConfig::applyAndReboot()
{
162
    // Guard against the case of an edit where we didn't receive all params yet
Lorenz Meier's avatar
Lorenz Meier committed
163
    if (selectedId <= 0)
164 165 166 167 168 169 170 171 172 173 174 175 176 177
    {
        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;

178 179
    if (paramMgr->countOnboardParams() == 0 &&
            paramMgr->countPendingParams() == 0)
180
    {
181 182
        paramMgr->requestParameterList();
        QGC::SLEEP::msleep(300);
183 184
    }

185 186
    QList<int> components = paramMgr->getComponentForParam("SYS_AUTOSTART");

187
    // Guard against the case of an edit where we didn't receive all params yet
188
    if (paramMgr->countPendingParams() > 0 || components.count() == 0)
189 190 191 192 193 194 195
    {
        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();
196 197

        return;
198 199 200 201 202 203 204 205 206 207 208 209 210 211
    }

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

212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 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 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342
    // 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()));
}

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

        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;
            return;
        }
        qDebug() << "PENDING PARAMS REBOOT AFTER:" << pendingParams;
        pendingParams++;
        return;
    }
343 344 345 346 347 348
}

void QGCPX4AirframeConfig::setAutoConfig(bool enabled)
{
    if (!mav)
        return;
349
    paramMgr->setPendingParam(0, "SYS_AUTOCONFIG", (qint32) ((enabled) ? 1 : 0));
350 351 352 353
}

void QGCPX4AirframeConfig::flyingWingSelected()
{
354
    flyingWingSelected(ui->flyingWingComboBox->currentIndex());
Lorenz Meier's avatar
Lorenz Meier committed
355 356
}

357 358 359 360 361 362 363 364
void QGCPX4AirframeConfig::flyingWingSelected(int index)
{
    int system_index = ui->flyingWingComboBox->itemData(index).toInt();
    setAirframeID(system_index);
}

void QGCPX4AirframeConfig::planeSelected()
{
365
    planeSelected(ui->planeComboBox->currentIndex());
366 367 368 369 370 371 372 373 374 375 376
}

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


void QGCPX4AirframeConfig::quadXSelected()
{
377
    quadXSelected(ui->quadXComboBox->currentIndex());
378 379 380 381 382 383 384 385 386 387
}

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

void QGCPX4AirframeConfig::quadPlusSelected()
{
388
    quadPlusSelected(ui->quadPlusComboBox->currentIndex());
389 390 391 392 393 394 395 396 397 398
}

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

void QGCPX4AirframeConfig::hexaXSelected()
{
399
    hexaXSelected(ui->hexaXComboBox->currentIndex());
400 401 402 403 404 405 406 407 408 409
}

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

void QGCPX4AirframeConfig::hexaPlusSelected()
{
410
    hexaPlusSelected(ui->hexaPlusComboBox->currentIndex());
411 412 413 414 415 416 417 418 419 420
}

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

void QGCPX4AirframeConfig::octoXSelected()
{
421
    octoXSelected(ui->octoXComboBox->currentIndex());
422 423 424 425 426 427 428 429 430 431
}

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

void QGCPX4AirframeConfig::octoPlusSelected()
{
432
    octoPlusSelected(ui->octoPlusComboBox->currentIndex());
433 434 435 436 437 438 439 440 441 442
}

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

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

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


Lorenz Meier's avatar
Lorenz Meier committed
453 454 455 456
QGCPX4AirframeConfig::~QGCPX4AirframeConfig()
{
    delete ui;
}