MainWindow.cc 35.4 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25

======================================================================*/

/**
 * @file
26
 *   @brief Implementation of class MainWindow
27
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46
 */

#include <QSettings>
#include <QDockWidget>
#include <QNetworkInterface>
#include <QMessageBox>
#include <QDebug>
#include <QTimer>
#include <QHostInfo>

#include "MG.h"
#include "MAVLinkSimulationLink.h"
#include "SerialLink.h"
#include "UDPLink.h"
#include "MAVLinkProtocol.h"
#include "CommConfigurationWindow.h"
#include "WaypointList.h"
#include "MainWindow.h"
#include "JoystickWidget.h"
pixhawk's avatar
pixhawk committed
47
#include "GAudioOutput.h"
lm's avatar
lm committed
48
#include "QMap3DWidget.h"
pixhawk's avatar
pixhawk committed
49

lm's avatar
lm committed
50 51 52 53
// FIXME Move
#include "PxQuadMAV.h"
#include "SlugsMAV.h"

pixhawk's avatar
pixhawk committed
54 55 56 57 58 59 60 61 62 63

#include "LogCompressor.h"

/**
* Create new mainwindow. The constructor instantiates all parts of the user
* interface. It does NOT show the mainwindow. To display it, call the show()
* method.
*
* @see QMainWindow::show()
**/
64
MainWindow::MainWindow(QWidget *parent) :
pixhawk's avatar
pixhawk committed
65 66
        QMainWindow(parent),
        settings()
pixhawk's avatar
pixhawk committed
67
{
68 69 70
    this->hide();
    this->setVisible(false);

pixhawk's avatar
pixhawk committed
71 72 73
    // Setup user interface
    ui.setupUi(this);

74 75 76 77 78 79 80
    buildWidgets();

    connectWidgets();

    arrangeCenterStack();

    configureWindowName();
pixhawk's avatar
pixhawk committed
81 82 83 84 85 86 87

    // Add status bar
    setStatusBar(createStatusBar());

    // Set the application style (not the same as a style sheet)
    // Set the style to Plastique
    qApp->setStyle("plastique");
88

pixhawk's avatar
pixhawk committed
89 90 91 92
    // Set style sheet as last step
    reloadStylesheet();


93 94 95
    // Create actions
    connectActions();

96
    // Load widgets and show application windowa
97 98 99 100
    loadWidgets();

    // Adjust the size
    adjustSize();
pixhawk's avatar
pixhawk committed
101 102
}

pixhawk's avatar
pixhawk committed
103
MainWindow::~MainWindow()
pixhawk's avatar
pixhawk committed
104 105 106 107 108
{
    delete statusBar;
    statusBar = NULL;
}

109 110 111

void MainWindow::buildWidgets()
{
pixhawk's avatar
pixhawk committed
112 113 114 115 116 117 118 119
    //FIXME: memory of acceptList will never be freed again
    QStringList* acceptList = new QStringList();
    acceptList->append("roll IMU");
    acceptList->append("pitch IMU");
    acceptList->append("yaw IMU");
    acceptList->append("rollspeed IMU");
    acceptList->append("pitchspeed IMU");
    acceptList->append("yawspeed IMU");
120

pixhawk's avatar
pixhawk committed
121 122 123 124
    //FIXME: memory of acceptList2 will never be freed again
    QStringList* acceptList2 = new QStringList();
    acceptList2->append("Battery");
    acceptList2->append("Pressure");
125

pixhawk's avatar
pixhawk committed
126 127
    //TODO:  move protocol outside UI
    mavlink     = new MAVLinkProtocol();
128

pixhawk's avatar
pixhawk committed
129 130 131 132 133 134
    // Center widgets
    linechartWidget   = new Linecharts(this);
    hudWidget         = new HUD(640, 480, this);
    mapWidget         = new MapWidget(this);
    protocolWidget    = new XMLCommProtocolWidget(this);
    dataplotWidget    = new QGCDataPlot2D(this);
lm's avatar
lm committed
135
    map3DWidget       = new QMap3DWidget(this);
136

pixhawk's avatar
pixhawk committed
137 138 139
    // Dock widgets
    controlDockWidget = new QDockWidget(tr("Control"), this);
    controlDockWidget->setWidget( new UASControlWidget(this) );
140

pixhawk's avatar
pixhawk committed
141 142
    listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
    listDockWidget->setWidget( new UASListWidget(this) );
143

pixhawk's avatar
pixhawk committed
144 145
    waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
    waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
146

pixhawk's avatar
pixhawk committed
147 148
    infoDockWidget = new QDockWidget(tr("Status Details"), this);
    infoDockWidget->setWidget( new UASInfoWidget(this) );
149

pixhawk's avatar
pixhawk committed
150 151
    detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
    detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
152

pixhawk's avatar
pixhawk committed
153 154
    debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
    debugConsoleDockWidget->setWidget( new DebugConsole(this) );
155

pixhawk's avatar
pixhawk committed
156 157
    parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
    parametersDockWidget->setWidget( new ParameterInterface(this) );
158

pixhawk's avatar
pixhawk committed
159 160
    watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
    watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
161

pixhawk's avatar
pixhawk committed
162 163
    hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
    hsiDockWidget->setWidget( new HSIDisplay(this) );
164

pixhawk's avatar
pixhawk committed
165 166
    headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
    headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
167

pixhawk's avatar
pixhawk committed
168 169
    headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
    headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
170

pixhawk's avatar
pixhawk committed
171 172
    rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
    rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
173

174 175 176
    headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
    headUpDockWidget->setWidget( new HUD(320, 240, this));

pixhawk's avatar
pixhawk committed
177 178 179
    // Dialogue widgets
    //FIXME: free memory in destructor
    joystick    = new JoystickInput();
180

181 182 183
    slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
    slugsDataWidget->setWidget( new SlugsDataSensorView(this));

184 185 186
    slugsPIDControlWidget = new QDockWidget(tr("PID Control"), this);
    slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));

187 188
    slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
    slugsHilSimWidget->setWidget( new SlugsHilSim(this));
189

190 191 192
    slugsCamControlWidget = new QDockWidget(tr("Video Camera Control"), this);
    slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));

193 194
}

pixhawk's avatar
pixhawk committed
195 196 197
/**
 * Connect all signals and slots of the main window widgets
 */
198 199
void MainWindow::connectWidgets()
{
pixhawk's avatar
pixhawk committed
200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220
    if (linechartWidget)
    {
        connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
                linechartWidget, SLOT(addSystem(UASInterface*)));
        connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
                linechartWidget, SLOT(selectSystem(int)));
        connect(linechartWidget, SIGNAL(logfileWritten(QString)),
                this, SLOT(loadDataView(QString)));
    }
    if (infoDockWidget && infoDockWidget->widget())
    {
        connect(mavlink, SIGNAL(receiveLossChanged(int, float)),
                infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
    }
    if (mapWidget && waypointsDockWidget->widget())
    {
        // clear path create on the map
        connect(waypointsDockWidget->widget(), SIGNAL(clearPathclicked()), mapWidget, SLOT(clearPath()));
        // add Waypoint widget in the WaypointList widget when mouse clicked
        connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));
        // it notifies that a waypoint global goes to do create
221
        connect(mapWidget, SIGNAL(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF)));
pixhawk's avatar
pixhawk committed
222
        connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
223 224 225

        // it notifies that a waypoint global goes to do create and a map graphic too
        connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
226
        // it notifies that a waypoint global change it¥s position by spinBox on Widget WaypointView
227
        connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
228 229 230

        connect(slugsCamControlWidget->widget(),SIGNAL(viewCamBorderAtMap(bool)),mapWidget,SLOT(drawBorderCamAtMap(bool)));
         connect(slugsCamControlWidget->widget(),SIGNAL(changeCamPosition(double,double,QString)),mapWidget,SLOT(updateCameraPosition(double,double, QString)));
pixhawk's avatar
pixhawk committed
231
    }
232

233 234 235 236 237 238 239 240
    if (slugsHilSimWidget && slugsHilSimWidget->widget()){
      connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
              slugsHilSimWidget->widget(), SLOT(activeUasSet(UASInterface*)));
    }

    if (slugsDataWidget && slugsDataWidget->widget()){
      connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
              slugsDataWidget->widget(), SLOT(setActiveUAS(UASInterface*)));
241 242
    }

243

244 245
}

246 247
void MainWindow::arrangeCenterStack()
{
248

pixhawk's avatar
pixhawk committed
249 250 251 252 253
    QStackedWidget *centerStack = new QStackedWidget(this);
    if (!centerStack) return;
    if (linechartWidget) centerStack->addWidget(linechartWidget);
    if (protocolWidget) centerStack->addWidget(protocolWidget);
    if (mapWidget) centerStack->addWidget(mapWidget);
lm's avatar
lm committed
254
    if (map3DWidget) centerStack->addWidget(map3DWidget);
pixhawk's avatar
pixhawk committed
255 256
    if (hudWidget) centerStack->addWidget(hudWidget);
    if (dataplotWidget) centerStack->addWidget(dataplotWidget);
257

pixhawk's avatar
pixhawk committed
258
    setCentralWidget(centerStack);
259 260
}

261 262
void MainWindow::configureWindowName()
{
pixhawk's avatar
pixhawk committed
263 264 265
    QList<QHostAddress> hostAddresses = QNetworkInterface::allAddresses();
    QString windowname = qApp->applicationName() + " " + qApp->applicationVersion();
    bool prevAddr = false;
266

pixhawk's avatar
pixhawk committed
267
    windowname.append(" (" + QHostInfo::localHostName() + ": ");
268

pixhawk's avatar
pixhawk committed
269 270 271 272 273 274 275 276 277 278
    for (int i = 0; i < hostAddresses.size(); i++)
    {
        // Exclude loopback IPv4 and all IPv6 addresses
        if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":"))
        {
            if(prevAddr) windowname.append("/");
            windowname.append(hostAddresses.at(i).toString());
            prevAddr = true;
        }
    }
279

pixhawk's avatar
pixhawk committed
280
    windowname.append(")");
281

pixhawk's avatar
pixhawk committed
282
    setWindowTitle(windowname);
283 284

#ifndef Q_WS_MAC
pixhawk's avatar
pixhawk committed
285
    //qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png"));
286 287 288
#endif
}

pixhawk's avatar
pixhawk committed
289
QStatusBar* MainWindow::createStatusBar()
pixhawk's avatar
pixhawk committed
290 291 292 293 294 295 296 297
{
    QStatusBar* bar = new QStatusBar();
    /* Add status fields and messages */
    /* Enable resize grip in the bottom right corner */
    bar->setSizeGripEnabled(true);
    return bar;
}

pixhawk's avatar
pixhawk committed
298
void MainWindow::startVideoCapture()
pixhawk's avatar
pixhawk committed
299 300 301 302 303 304 305 306 307 308 309
{
    QString format = "bmp";
    QString initialPath = QDir::currentPath() + tr("/untitled.") + format;

    QString screenFileName = QFileDialog::getSaveFileName(this, tr("Save As"),
                                                          initialPath,
                                                          tr("%1 Files (*.%2);;All Files (*)")
                                                          .arg(format.toUpper())
                                                          .arg(format));
    delete videoTimer;
    videoTimer = new QTimer(this);
310 311 312
    //videoTimer->setInterval(40);
    //connect(videoTimer, SIGNAL(timeout()), this, SLOT(saveScreen()));
    //videoTimer->stop();
pixhawk's avatar
pixhawk committed
313 314
}

pixhawk's avatar
pixhawk committed
315
void MainWindow::stopVideoCapture()
pixhawk's avatar
pixhawk committed
316 317 318 319 320 321
{
    videoTimer->stop();

    // TODO Convert raw images to PNG
}

pixhawk's avatar
pixhawk committed
322
void MainWindow::saveScreen()
pixhawk's avatar
pixhawk committed
323 324 325 326 327 328 329 330 331 332
{
    QPixmap window = QPixmap::grabWindow(this->winId());
    QString format = "bmp";

    if (!screenFileName.isEmpty())
    {
        window.save(screenFileName, format.toAscii());
    }
}

333 334 335 336 337 338
/**
 * Reload the style sheet from disk. The function tries to load "qgroundcontrol.css" from the application
 * directory (which by default does not exist). If it fails, it will load the bundled default CSS
 * from memory.
 * To customize the application, just create a qgroundcontrol.css file in the application directory
 */
pixhawk's avatar
pixhawk committed
339
void MainWindow::reloadStylesheet()
pixhawk's avatar
pixhawk committed
340 341
{
    // Load style sheet
342 343 344 345 346
    QFile* styleSheet = new QFile(QCoreApplication::applicationDirPath() + "/qgroundcontrol.css");
    if (!styleSheet->exists())
    {
        styleSheet = new QFile(":/images/style-mission.css");
    }
347 348
    if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text))
    {
349 350
        QString style = QString(styleSheet->readAll());
        style.replace("ICONDIR", QCoreApplication::applicationDirPath()+ "/images/");
pixhawk's avatar
pixhawk committed
351
        qApp->setStyleSheet(style);
352 353 354
    }
    else
    {
355
        qDebug() << "Style not set:" << styleSheet->fileName() << "opened: " << styleSheet->isOpen();
pixhawk's avatar
pixhawk committed
356
    }
357
    delete styleSheet;
pixhawk's avatar
pixhawk committed
358 359
}

pixhawk's avatar
pixhawk committed
360
void MainWindow::showStatusMessage(const QString& status, int timeout)
pixhawk's avatar
pixhawk committed
361 362 363 364
{
    statusBar->showMessage(status, timeout);
}

365
void MainWindow::showStatusMessage(const QString& status)
pixhawk's avatar
pixhawk committed
366
{
367
    statusBar->showMessage(status, 5);
pixhawk's avatar
pixhawk committed
368 369 370 371 372 373
}

/**
* @brief Create all actions associated to the main window
*
**/
pixhawk's avatar
pixhawk committed
374
void MainWindow::connectActions()
pixhawk's avatar
pixhawk committed
375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393
{
    // Connect actions from ui
    connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink()));

    // Connect internal actions
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*)));

    // Connect user interface controls
    connect(ui.actionLiftoff, SIGNAL(triggered()), UASManager::instance(), SLOT(launchActiveUAS()));
    connect(ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS()));
    connect(ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS()));
    connect(ui.actionEmergency_Kill, SIGNAL(triggered()), UASManager::instance(), SLOT(killActiveUAS()));

    connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS()));

    // User interface actions
    connect(ui.actionPilotView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
    connect(ui.actionEngineerView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
    connect(ui.actionOperatorView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
394
    connect(ui.action3DView, SIGNAL(triggered()), this, SLOT(load3DView()));
395
    connect(ui.actionShow_full_view, SIGNAL(triggered()), this, SLOT(loadAllView()));
396
    connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
397
    connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
pixhawk's avatar
pixhawk committed
398
    connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
399
    connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView()));
400 401 402 403
    connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
    connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
    connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));

pixhawk's avatar
pixhawk committed
404 405
    // Joystick configuration
    connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
406

407 408
    // Slugs View
    connect(ui.actionShow_Slugs_View, SIGNAL(triggered()), this, SLOT(loadSlugsView()));
409

410 411 412
    //GlobalOperatorView
   // connect(ui.actionGlobalOperatorView,SIGNAL(triggered()),waypointsDockWidget->widget(),SLOT())

pixhawk's avatar
pixhawk committed
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 453 454 455 456
void MainWindow::showHelp()
{
    if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/user_guide")))
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Could not open help in browser");
        msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/user_guide in a browser.");
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

void MainWindow::showCredits()
{
    if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/credits")))
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Could not open credits in browser");
        msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/credits in a browser.");
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

void MainWindow::showRoadMap()
{
    if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/roadmap")))
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Could not open roadmap in browser");
        msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/roadmap in a browser.");
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

pixhawk's avatar
pixhawk committed
457
void MainWindow::configure()
pixhawk's avatar
pixhawk committed
458 459 460 461
{
    joystickWidget = new JoystickWidget(joystick, this);
}

pixhawk's avatar
pixhawk committed
462
void MainWindow::addLink()
pixhawk's avatar
pixhawk committed
463 464 465 466 467 468 469 470 471 472 473 474 475 476 477
{
    SerialLink* link = new SerialLink();
    // TODO This should be only done in the dialog itself

    LinkManager::instance()->addProtocol(link, mavlink);

    CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);

    ui.menuNetwork->addAction(commWidget->getAction());

    commWidget->show();

    // TODO Implement the link removal!
}

pixhawk's avatar
pixhawk committed
478 479
void MainWindow::addLink(LinkInterface *link)
{
480
    LinkManager::instance()->addProtocol(link, mavlink);
pixhawk's avatar
pixhawk committed
481 482 483 484 485 486 487
    CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
    ui.menuNetwork->addAction(commWidget->getAction());

    // Special case for simulationlink
    MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
    if (sim)
    {
488
        //connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
pixhawk's avatar
pixhawk committed
489 490 491 492
        connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
    }
}

pixhawk's avatar
pixhawk committed
493
void MainWindow::UASCreated(UASInterface* uas)
pixhawk's avatar
pixhawk committed
494 495 496
{
    // Connect the UAS to the full user interface

497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528
    if (uas != NULL)
    {
        QIcon icon;
        // Set matching icon
        switch (uas->getSystemType())
        {
        case 0:
            icon = QIcon(":/images/mavs/generic.svg");
            break;
        case 1:
            icon = QIcon(":/images/mavs/fixed-wing.svg");
            break;
        case 2:
            icon = QIcon(":/images/mavs/quadrotor.svg");
            break;
        case 3:
            icon = QIcon(":/images/mavs/coaxial.svg");
            break;
        case 4:
            icon = QIcon(":/images/mavs/helicopter.svg");
            break;
        case 5:
            icon = QIcon(":/images/mavs/groundstation.svg");
            break;
        default:
            icon = QIcon(":/images/mavs/unknown.svg");
            break;
        }

        ui.menuConnected_Systems->addAction(icon, tr("Select %1 for control").arg(uas->getUASName()), uas, SLOT(setSelected()));

        // FIXME Should be not inside the mainwindow
529 530
        if (debugConsoleDockWidget)
        {
pixhawk's avatar
pixhawk committed
531 532 533 534 535 536
            DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
            if (debugConsole)
            {
                connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
                        debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
            }
537
        }
538 539

        // Health / System status indicator
540 541
        if (infoDockWidget)
        {
pixhawk's avatar
pixhawk committed
542 543 544 545 546
            UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
            if (infoWidget)
            {
                infoWidget->addUAS(uas);
            }
547
        }
548 549

        // UAS List
550 551
        if (listDockWidget)
        {
pixhawk's avatar
pixhawk committed
552 553 554 555 556
            UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
            if (listWidget)
            {
                listWidget->addUAS(uas);
            }
557
        }
558 559 560 561 562 563 564 565 566 567 568

        // Camera view
        //camera->addUAS(uas);

        // Revalidate UI
        // TODO Stylesheet reloading should in theory not be necessary
        reloadStylesheet();

        // Check which type this UAS is of
        PxQuadMAV* mav = dynamic_cast<PxQuadMAV*>(uas);
        if (mav) loadPixhawkView();
569

570 571 572 573 574 575
        if (slugsDataWidget) {
          SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
          if (dataWidget) {
            SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
            if (mav2) {
              dataWidget->addUAS(uas);
576 577
              //loadSlugsView();
              loadGlobalOperatorView();
578 579
            }
          }
580
        }
581
    }
pixhawk's avatar
pixhawk committed
582 583
}

584 585 586
/**
 * Clears the current view completely
 */
pixhawk's avatar
pixhawk committed
587
void MainWindow::clearView()
pixhawk's avatar
pixhawk committed
588 589
{ 
    // Halt HUD
590 591 592 593 594 595 596 597 598
    if (hudWidget) hudWidget->stop();
    // Disable linechart
    if (linechartWidget) linechartWidget->setActive(false);
    // Halt HDDs
    if (headDown1DockWidget)
    {
        HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown1DockWidget->widget() );
        if (hddWidget) hddWidget->stop();
    }
pixhawk's avatar
pixhawk committed
599
    if (headDown2DockWidget)
600 601 602 603 604 605 606 607 608 609
    {
        HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown2DockWidget->widget() );
        if (hddWidget) hddWidget->stop();
    }
    // Halt HSI
    if (hsiDockWidget)
    {
        HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
        if (hsi) hsi->stop();
    }
pixhawk's avatar
pixhawk committed
610

611 612
    // Remove all dock widgets from main window
    QObjectList childList( this->children() );
pixhawk's avatar
pixhawk committed
613

614 615 616
    QObjectList::iterator i;
    QDockWidget* dockWidget;
    for (i = childList.begin(); i != childList.end(); ++i)
pixhawk's avatar
pixhawk committed
617
    {
618 619
        dockWidget = dynamic_cast<QDockWidget*>(*i);
        if (dockWidget)
pixhawk's avatar
pixhawk committed
620
        {
621 622 623 624 625
            // Remove dock widget from main window
            this->removeDockWidget(dockWidget);
            // Deletion of dockWidget would also delete all child
            // widgets of dockWidget
            // Is there a way to unset a widget from QDockWidget?
pixhawk's avatar
pixhawk committed
626 627 628 629
        }
    }
}

lm's avatar
lm committed
630 631 632 633 634 635
void MainWindow::loadSlugsView()
{
    clearView();
    // Engineer view, used in EMAV2009

    // LINE CHART
636 637 638 639 640 641 642 643 644
    if (linechartWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            linechartWidget->setActive(true);
            centerStack->setCurrentWidget(linechartWidget);
        }
    }
lm's avatar
lm committed
645 646

    // UAS CONTROL
647 648 649 650 651
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
lm's avatar
lm committed
652 653

    // UAS LIST
654 655 656 657 658
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
lm's avatar
lm committed
659 660

    // UAS STATUS
661 662 663 664 665
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
lm's avatar
lm committed
666 667 668


    // WAYPOINT LIST
669 670 671 672 673
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
lm's avatar
lm committed
674 675

    // DEBUG CONSOLE
676 677 678 679 680
    if (debugConsoleDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
        debugConsoleDockWidget->show();
    }
lm's avatar
lm committed
681

682 683
    // Slugs Data View
    if (slugsDataWidget)
684
    {
685 686
        addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget);
        slugsDataWidget->show();
687
    }
lm's avatar
lm committed
688

689 690 691 692 693 694
    // Slugs Data View
    if (slugsHilSimWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, slugsHilSimWidget);
        slugsHilSimWidget->show();
    }
lm's avatar
lm committed
695 696 697 698 699 700 701 702
    this->show();
}

void MainWindow::loadPixhawkView()
{
    clearView();
    // Engineer view, used in EMAV2009

703 704
    // 3D map
    if (map3DWidget)
705 706 707 708
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
709 710
            //map3DWidget->setActive(true);
            centerStack->setCurrentWidget(map3DWidget);
711 712
        }
    }
lm's avatar
lm committed
713 714

    // UAS CONTROL
715 716 717 718 719
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
lm's avatar
lm committed
720

721 722 723 724 725 726 727 728 729 730 731 732
    // HORIZONTAL SITUATION INDICATOR
    if (hsiDockWidget)
    {
        HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
        if (hsi)
        {
            hsi->start();
            addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
            hsiDockWidget->show();
        }
    }

lm's avatar
lm committed
733
    // UAS LIST
734 735 736 737 738
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
lm's avatar
lm committed
739 740

    // UAS STATUS
741 742 743 744 745
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
lm's avatar
lm committed
746 747

    // WAYPOINT LIST
748 749 750 751 752
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
lm's avatar
lm committed
753 754

    // DEBUG CONSOLE
755 756 757 758 759
    if (debugConsoleDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
        debugConsoleDockWidget->show();
    }
lm's avatar
lm committed
760 761

    // ONBOARD PARAMETERS
762 763 764 765 766
    if (parametersDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
        parametersDockWidget->show();
    }
lm's avatar
lm committed
767 768 769 770

    this->show();
}

771 772 773
void MainWindow::loadDataView()
{
    clearView();
774 775 776 777 778 779 780 781

    // DATAPLOT
    if (dataplotWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
            centerStack->setCurrentWidget(dataplotWidget);
    }
782 783
}

784 785 786
void MainWindow::loadDataView(QString fileName)
{
    clearView();
pixhawk's avatar
pixhawk committed
787

788 789 790 791 792 793 794 795 796 797
    // DATAPLOT
    if (dataplotWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(dataplotWidget);
            dataplotWidget->loadFile(fileName);
        }
    }
798 799
}

pixhawk's avatar
pixhawk committed
800
void MainWindow::loadPilotView()
pixhawk's avatar
pixhawk committed
801 802 803 804
{
    clearView();

    // HEAD UP DISPLAY
805 806 807 808 809 810 811 812 813
    if (hudWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(hudWidget);
            hudWidget->start();
        }
    }
pixhawk's avatar
pixhawk committed
814 815

    //connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*)));
816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836
    if (headDown1DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
            headDown1DockWidget->show();
            hdd->start();
        }
        
    }
    if (headDown2DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
            headDown2DockWidget->show();
            hdd->start();
        }
    }
pixhawk's avatar
pixhawk committed
837

pixhawk's avatar
pixhawk committed
838 839 840
    this->show();
}

pixhawk's avatar
pixhawk committed
841
void MainWindow::loadOperatorView()
pixhawk's avatar
pixhawk committed
842 843 844
{
    clearView();

845
    // MAP
846 847 848 849 850 851 852 853
    if (mapWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(mapWidget);
        }
    }
pixhawk's avatar
pixhawk committed
854 855

    // UAS CONTROL
856 857 858 859 860
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
861 862

    // UAS LIST
863 864 865 866 867
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
868 869

    // UAS STATUS
870 871 872 873 874
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
875 876

    // WAYPOINT LIST
877 878 879 880 881
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
882

lm's avatar
lm committed
883
    // HORIZONTAL SITUATION INDICATOR
884 885 886 887 888 889 890 891 892 893
    if (hsiDockWidget)
    {
        HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
        if (hsi)
        {
            addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
            hsiDockWidget->show();
            hsi->start();
        }
    }
pixhawk's avatar
pixhawk committed
894 895

    // OBJECT DETECTION
896 897 898 899 900
    if (detectionDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
        detectionDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
901

pixhawk's avatar
pixhawk committed
902
    // PROCESS CONTROL
903 904 905 906 907 908
    if (watchdogControlDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
        watchdogControlDockWidget->show();
    }

pixhawk's avatar
pixhawk committed
909 910 911
    this->show();
}

912 913 914 915 916
void MainWindow::loadGlobalOperatorView()
{
    clearView();

    // MAP
917 918 919 920 921 922 923 924
    if (mapWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(mapWidget);
        }
    }
925

tecnosapiens's avatar
tecnosapiens committed
926 927
    // WAYPOINT LIST
    if (waypointsDockWidget)
928
    {
tecnosapiens's avatar
tecnosapiens committed
929 930
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
931

932
    }
933

tecnosapiens's avatar
tecnosapiens committed
934 935
    // Slugs Data View
    if (slugsDataWidget)
936
    {
tecnosapiens's avatar
tecnosapiens committed
937 938
        addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget);
        slugsDataWidget->show();
939
    }
940

941 942 943 944 945 946 947
    // Slugs Data View
    if (slugsPIDControlWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget);
        slugsPIDControlWidget->show();
    }

948 949
    if (slugsCamControlWidget)
    {
950
        addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
951 952 953
        slugsCamControlWidget->show();
    }

954

tecnosapiens's avatar
tecnosapiens committed
955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976

//    // UAS CONTROL
//    if (controlDockWidget)
//    {
//        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
//        controlDockWidget->show();
//    }

//    // UAS LIST
//    if (listDockWidget)
//    {
//        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
//        listDockWidget->show();
//    }

//    // UAS STATUS
//    if (infoDockWidget)
//    {
//        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
//        infoDockWidget->show();
//    }

977

978 979 980 981 982 983 984 985 986 987 988
//    // HORIZONTAL SITUATION INDICATOR
//    if (hsiDockWidget)
//    {
//        HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
//        if (hsi)
//        {
//            addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
//            hsiDockWidget->show();
//            hsi->start();
//        }
//    }
989 990

    // PROCESS CONTROL
tecnosapiens's avatar
tecnosapiens committed
991 992 993 994 995
//    if (watchdogControlDockWidget)
//    {
//        addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
//        watchdogControlDockWidget->show();
//    }
pixhawk's avatar
pixhawk committed
996

997
    // HEAD UP DISPLAY
tecnosapiens's avatar
tecnosapiens committed
998 999 1000 1001 1002
//    if (headUpDockWidget)
//    {
//        addDockWidget(Qt::RightDockWidgetArea, headUpDockWidget);
//        // FIXME Replace with default ->show() call
//        HUD* hud = dynamic_cast<HUD*>(headUpDockWidget->widget());
pixhawk's avatar
pixhawk committed
1003

tecnosapiens's avatar
tecnosapiens committed
1004 1005 1006 1007 1008 1009
//        if (hud)
//        {
//            headUpDockWidget->show();
//            hud->start();
//        }
//    }
pixhawk's avatar
pixhawk committed
1010 1011 1012

}

1013
void MainWindow::load3DView()
pixhawk's avatar
pixhawk committed
1014
{
1015
            clearView();
pixhawk's avatar
pixhawk committed
1016

1017 1018 1019 1020 1021 1022 1023 1024 1025 1026
            // 3D map
            if (map3DWidget)
            {
                QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
                if (centerStack)
                {
                    //map3DWidget->setActive(true);
                    centerStack->setCurrentWidget(map3DWidget);
                }
            }
pixhawk's avatar
pixhawk committed
1027

1028 1029 1030 1031 1032 1033
            // UAS CONTROL
            if (controlDockWidget)
            {
                addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
                controlDockWidget->show();
            }
pixhawk's avatar
pixhawk committed
1034

1035 1036 1037 1038 1039 1040
            // UAS LIST
            if (listDockWidget)
            {
                addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
                listDockWidget->show();
            }
1041

1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062
            // WAYPOINT LIST
            if (waypointsDockWidget)
            {
                addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
                waypointsDockWidget->show();
            }

            // HORIZONTAL SITUATION INDICATOR
            if (hsiDockWidget)
            {
                HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
                if (hsi)
                {
                    hsi->start();
                    addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
                    hsiDockWidget->show();
                }
            }

            this->show();
        }
pixhawk's avatar
pixhawk committed
1063

pixhawk's avatar
pixhawk committed
1064
void MainWindow::loadEngineerView()
pixhawk's avatar
pixhawk committed
1065 1066 1067 1068 1069
{
    clearView();
    // Engineer view, used in EMAV2009

    // LINE CHART
1070 1071 1072 1073 1074 1075 1076 1077 1078
    if (linechartWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            linechartWidget->setActive(true);
            centerStack->setCurrentWidget(linechartWidget);
        }
    }
pixhawk's avatar
pixhawk committed
1079 1080

    // UAS CONTROL
1081 1082 1083 1084 1085
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
1086 1087

    // UAS LIST
1088 1089 1090 1091 1092
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
1093 1094

    // UAS STATUS
1095 1096 1097 1098 1099
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
1100

lm's avatar
lm committed
1101
    // WAYPOINT LIST
1102 1103 1104 1105 1106
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
1107 1108

    // DEBUG CONSOLE
1109 1110 1111 1112 1113
    if (debugConsoleDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
        debugConsoleDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
1114

lm's avatar
lm committed
1115
    // ONBOARD PARAMETERS
1116 1117 1118 1119 1120
    if (parametersDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
        parametersDockWidget->show();
    }
lm's avatar
lm committed
1121

1122 1123 1124 1125 1126 1127 1128
    // RADIO CONTROL VIEW
    if (rcViewDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
        rcViewDockWidget->show();
    }

pixhawk's avatar
pixhawk committed
1129 1130 1131
    this->show();
}

1132 1133 1134
void MainWindow::loadMAVLinkView()
{
    clearView();
1135 1136 1137 1138 1139 1140 1141 1142 1143 1144

    if (protocolWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(protocolWidget);
        }
    }

1145
    this->show();
1146 1147
}

1148 1149
void MainWindow::loadAllView()
{
1150 1151
    clearView();

1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172
    if (headDown1DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
            headDown1DockWidget->show();
            hdd->start();
        }
        
    }
    if (headDown2DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
            headDown2DockWidget->show();
            hdd->start();
        }
    }
1173 1174

    // UAS CONTROL
1175 1176 1177 1178 1179
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
1180 1181

    // UAS LIST
1182 1183 1184 1185 1186
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
1187 1188

    // UAS STATUS
1189 1190 1191 1192 1193
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
1194 1195

    // WAYPOINT LIST
1196 1197 1198 1199 1200
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
1201 1202

    // DEBUG CONSOLE
1203 1204 1205 1206 1207
    if (debugConsoleDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
        debugConsoleDockWidget->show();
    }
1208 1209

    // OBJECT DETECTION
1210 1211
    if (detectionDockWidget)
    {
pixhawk's avatar
pixhawk committed
1212 1213
        addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
        detectionDockWidget->show();
1214
    }
1215 1216

    // LINE CHART
1217 1218 1219 1220 1221 1222 1223 1224 1225
    if (linechartWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            linechartWidget->setActive(true);
            centerStack->setCurrentWidget(linechartWidget);
        }
    }
1226 1227

    // ONBOARD PARAMETERS
1228 1229 1230 1231 1232
    if (parametersDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
        parametersDockWidget->show();
    }
1233 1234

    this->show();
1235 1236
}

pixhawk's avatar
pixhawk committed
1237
void MainWindow::loadWidgets()
pixhawk's avatar
pixhawk committed
1238
{
1239 1240
    //loadOperatorView();
    loadEngineerView();
pixhawk's avatar
pixhawk committed
1241 1242
    //loadPilotView();
}