/*=================================================================== ======================================================================*/ /** * @file * @brief Implementation of class MainWindow * @author Lorenz Meier */ #include #include #include #include #include #include #include #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" #include "GAudioOutput.h" #ifdef QGC_OSG_ENABLED #include "Q3DWidgetFactory.h" #endif // FIXME Move #include "PxQuadMAV.h" #include "SlugsMAV.h" #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() **/ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent), settings() { this->hide(); this->setVisible(false); // Setup user interface ui.setupUi(this); buildWidgets(); connectWidgets(); arrangeCenterStack(); configureWindowName(); // Add status bar //setStatusBar(createStatusBar()); // Set the application style (not the same as a style sheet) // Set the style to Plastique qApp->setStyle("plastique"); // Set style sheet as last step reloadStylesheet(); // Create actions connectActions(); // Load widgets and show application windowa loadWidgets(); // Adjust the size adjustSize(); // Set menu QMenu* widgetMenu = createDockWidgetMenu(); widgetMenu->setTitle("Widgets"); ui.menuBar->addMenu(widgetMenu); // QMenu* centerMenu = createCenterWidgetMenu(); // centerMenu->setTitle("Center"); // ui.menuBar->addMenu(centerMenu); this->show(); } MainWindow::~MainWindow() { delete statusBar; statusBar = NULL; } QMenu* MainWindow::createCenterWidgetMenu() { QMenu* menu = NULL; QStackedWidget* centerStack = dynamic_cast(centralWidget()); if (centerStack) { if (centerStack->count() > 0) { menu = new QMenu(this); for (int i = 0; i < centerStack->count(); ++i) { //menu->addAction(centerStack->widget(i)->actions()) } } } return menu; } QMenu* MainWindow::createDockWidgetMenu() { QMenu *menu = 0; #ifndef QT_NO_DOCKWIDGET QList dockwidgets = qFindChildren(this); if (dockwidgets.size()) { menu = new QMenu(this); for (int i = 0; i < dockwidgets.size(); ++i) { QDockWidget *dockWidget = dockwidgets.at(i); if (dockWidget->parentWidget() == this) { menu->addAction(dockwidgets.at(i)->toggleViewAction()); } } menu->addSeparator(); } #endif return menu; } //QList* MainWindow::getMainWidgets() //{ //} //QMenu* QMainWindow::getDockWidgetMenu() //{ // Q_D(QMainWindow); // QMenu *menu = 0; //#ifndef QT_NO_DOCKWIDGET // QList dockwidgets = qFindChildren(this); // if (dockwidgets.size()) { // menu = new QMenu(this); // for (int i = 0; i < dockwidgets.size(); ++i) { // QDockWidget *dockWidget = dockwidgets.at(i); // if (dockWidget->parentWidget() == this // && d->layout->contains(dockWidget)) { // menu->addAction(dockwidgets.at(i)->toggleViewAction()); // } // } // menu->addSeparator(); // } //#endif // QT_NO_DOCKWIDGET //#ifndef QT_NO_TOOLBAR // QList toolbars = qFindChildren(this); // if (toolbars.size()) { // if (!menu) // menu = new QMenu(this); // for (int i = 0; i < toolbars.size(); ++i) { // QToolBar *toolBar = toolbars.at(i); // if (toolBar->parentWidget() == this // && d->layout->contains(toolBar)) { // menu->addAction(toolbars.at(i)->toggleViewAction()); // } // } // } //#endif // Q_UNUSED(d); // return menu; //} void MainWindow::buildWidgets() { //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"); //FIXME: memory of acceptList2 will never be freed again QStringList* acceptList2 = new QStringList(); acceptList2->append("Battery"); acceptList2->append("Pressure"); //TODO: move protocol outside UI mavlink = new MAVLinkProtocol(); // Center widgets linechartWidget = new Linecharts(this); hudWidget = new HUD(320, 240, this); mapWidget = new MapWidget(this); protocolWidget = new XMLCommProtocolWidget(this); dataplotWidget = new QGCDataPlot2D(this); #ifdef QGC_OSG_ENABLED _3DWidget = Q3DWidgetFactory::get("PIXHAWK"); #endif #ifdef QGC_OSGEARTH_ENABLED _3DMapWidget = Q3DWidgetFactory::get("MAP3D"); #endif #if (defined Q_OS_WIN) | (defined Q_OS_MAC) gEarthWidget = new QGCGoogleEarthView(this); #endif // Dock widgets controlDockWidget = new QDockWidget(tr("Control"), this); controlDockWidget->setWidget( new UASControlWidget(this) ); addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget); controlDockWidget->hide(); infoDockWidget = new QDockWidget(tr("Status Details"), this); infoDockWidget->setWidget( new UASInfoWidget(this) ); addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget); //infoDockWidget->hide(); listDockWidget = new QDockWidget(tr("Unmanned Systems"), this); listDockWidget->setWidget( new UASListWidget(this) ); addDockWidget(Qt::BottomDockWidgetArea, listDockWidget); listDockWidget->hide(); waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this); waypointsDockWidget->setWidget( new WaypointList(this, NULL) ); addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->hide(); detectionDockWidget = new QDockWidget(tr("Object Recognition"), this); detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) ); addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget); detectionDockWidget->hide(); debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this); debugConsoleDockWidget->setWidget( new DebugConsole(this) ); addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget); parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this); parametersDockWidget->setWidget( new ParameterInterface(this) ); addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget); watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this); watchdogControlDockWidget->setWidget( new WatchdogControl(this) ); addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget); watchdogControlDockWidget->hide(); hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this); hsiDockWidget->setWidget( new HSIDisplay(this) ); addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget); headDown1DockWidget = new QDockWidget(tr("System Stats"), this); headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) ); addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget); headDown2DockWidget = new QDockWidget(tr("Payload Status"), this); headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) ); addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget); rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget); rcViewDockWidget->hide(); headUpDockWidget = new QDockWidget(tr("Control Indicator"), this); headUpDockWidget->setWidget( new HUD(320, 240, this)); this->addDockWidget(Qt::LeftDockWidgetArea, headUpDockWidget); // SLUGS slugsDataWidget = new QDockWidget(tr("Slugs Data"), this); slugsDataWidget->setWidget( new SlugsDataSensorView(this)); addDockWidget(Qt::LeftDockWidgetArea, slugsDataWidget); slugsDataWidget->hide(); slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this); slugsPIDControlWidget->setWidget(new SlugsPIDControl(this)); addDockWidget(Qt::BottomDockWidgetArea, slugsPIDControlWidget); slugsPIDControlWidget->hide(); slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this); slugsHilSimWidget->setWidget( new SlugsHilSim(this)); addDockWidget(Qt::BottomDockWidgetArea, slugsHilSimWidget); slugsHilSimWidget->hide(); slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this); slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this)); addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget); slugsCamControlWidget->hide(); //FIXME: free memory in destructor joystick = new JoystickInput(); } /** * Connect all signals and slots of the main window widgets */ void MainWindow::connectWidgets() { 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 //connect(mapWidget, SIGNAL(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF))); //connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) ); // 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))); // it notifies that a waypoint global change it¥s position by spinBox on Widget WaypointView //connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float))); // connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float))); connect(slugsCamControlWidget->widget(),SIGNAL(viewCamBorderAtMap(bool)),mapWidget,SLOT(drawBorderCamAtMap(bool))); connect(slugsCamControlWidget->widget(),SIGNAL(changeCamPosition(double,double,QString)),mapWidget,SLOT(updateCameraPosition(double,double, QString))); } 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*))); } } void MainWindow::arrangeCenterStack() { QStackedWidget *centerStack = new QStackedWidget(this); if (!centerStack) return; if (linechartWidget) centerStack->addWidget(linechartWidget); if (protocolWidget) centerStack->addWidget(protocolWidget); if (mapWidget) centerStack->addWidget(mapWidget); #ifdef QGC_OSG_ENABLED if (_3DWidget) centerStack->addWidget(_3DWidget); #endif #ifdef QGC_OSGEARTH_ENABLED if (_3DMapWidget) centerStack->addWidget(_3DMapWidget); #endif #if (defined Q_OS_WIN) | (defined Q_OS_MAC) if (gEarthWidget) centerStack->addWidget(gEarthWidget); #endif if (hudWidget) centerStack->addWidget(hudWidget); if (dataplotWidget) centerStack->addWidget(dataplotWidget); setCentralWidget(centerStack); } void MainWindow::configureWindowName() { QList hostAddresses = QNetworkInterface::allAddresses(); QString windowname = qApp->applicationName() + " " + qApp->applicationVersion(); bool prevAddr = false; windowname.append(" (" + QHostInfo::localHostName() + ": "); 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; } } windowname.append(")"); setWindowTitle(windowname); #ifndef Q_WS_MAC //qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png")); #endif } QStatusBar* MainWindow::createStatusBar() { QStatusBar* bar = new QStatusBar(); /* Add status fields and messages */ /* Enable resize grip in the bottom right corner */ bar->setSizeGripEnabled(true); return bar; } void MainWindow::startVideoCapture() { 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); //videoTimer->setInterval(40); //connect(videoTimer, SIGNAL(timeout()), this, SLOT(saveScreen())); //videoTimer->stop(); } void MainWindow::stopVideoCapture() { videoTimer->stop(); // TODO Convert raw images to PNG } void MainWindow::saveScreen() { QPixmap window = QPixmap::grabWindow(this->winId()); QString format = "bmp"; if (!screenFileName.isEmpty()) { window.save(screenFileName, format.toAscii()); } } /** * 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 */ void MainWindow::reloadStylesheet() { // Load style sheet QFile* styleSheet = new QFile(QCoreApplication::applicationDirPath() + "/qgroundcontrol.css"); if (!styleSheet->exists()) { styleSheet = new QFile(":/images/style-mission.css"); } if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text)) { QString style = QString(styleSheet->readAll()); style.replace("ICONDIR", QCoreApplication::applicationDirPath()+ "/images/"); qApp->setStyleSheet(style); } else { qDebug() << "Style not set:" << styleSheet->fileName() << "opened: " << styleSheet->isOpen(); } delete styleSheet; } void MainWindow::showStatusMessage(const QString& status, int timeout) { Q_UNUSED(status); Q_UNUSED(timeout); //statusBar->showMessage(status, timeout); } void MainWindow::showStatusMessage(const QString& status) { Q_UNUSED(status); //statusBar->showMessage(status, 5); } /** * @brief Create all actions associated to the main window * **/ void MainWindow::connectActions() { // 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())); #ifdef QGC_OSG_ENABLED connect(ui.action3DView, SIGNAL(triggered()), this, SLOT(load3DView())); #else ui.menuWindow->removeAction(ui.action3DView); #endif #ifdef QGC_OSGEARTH_ENABLED connect(ui.action3DMapView, SIGNAL(triggered()), this, SLOT(load3DMapView())); #else ui.menuWindow->removeAction(ui.action3DMapView); #endif connect(ui.actionShow_full_view, SIGNAL(triggered()), this, SLOT(loadAllView())); connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView())); connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView())); connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet())); connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView())); 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())); #if (defined Q_OS_WIN) | (defined Q_OS_MAC) connect(ui.actionGoogleEarthView, SIGNAL(triggered()), this, SLOT(loadGoogleEarthView())); #else ui.menuWindow->removeAction(ui.actionGoogleEarthView); #endif // Joystick configuration connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure())); // Slugs View connect(ui.actionShow_Slugs_View, SIGNAL(triggered()), this, SLOT(loadSlugsView())); //GlobalOperatorView // connect(ui.actionGlobalOperatorView,SIGNAL(triggered()),waypointsDockWidget->widget(),SLOT()) } 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(); } } void MainWindow::configure() { joystickWidget = new JoystickWidget(joystick, this); } void MainWindow::addLink() { 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! } void MainWindow::addLink(LinkInterface *link) { LinkManager::instance()->addProtocol(link, mavlink); CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); ui.menuNetwork->addAction(commWidget->getAction()); // Special case for simulationlink MAVLinkSimulationLink* sim = dynamic_cast(link); if (sim) { //connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64))); connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool))); } } void MainWindow::UASCreated(UASInterface* uas) { // Connect the UAS to the full user interface 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 if (debugConsoleDockWidget) { DebugConsole *debugConsole = dynamic_cast(debugConsoleDockWidget->widget()); if (debugConsole) { connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), debugConsole, SLOT(receiveTextMessage(int,int,int,QString))); } } // Health / System status indicator if (infoDockWidget) { UASInfoWidget *infoWidget = dynamic_cast(infoDockWidget->widget()); if (infoWidget) { infoWidget->addUAS(uas); } } // UAS List if (listDockWidget) { UASListWidget *listWidget = dynamic_cast(listDockWidget->widget()); if (listWidget) { listWidget->addUAS(uas); } } // 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(uas); if (mav) loadPixhawkView(); if (slugsDataWidget) { SlugsDataSensorView* dataWidget = dynamic_cast(slugsDataWidget->widget()); if (dataWidget) { SlugsMAV* mav2 = dynamic_cast(uas); if (mav2) { dataWidget->addUAS(uas); //loadSlugsView(); loadGlobalOperatorView(); } } } } } /** * Clears the current view completely */ void MainWindow::clearView() { // Halt HUD if (hudWidget) hudWidget->stop(); // Disable linechart if (linechartWidget) linechartWidget->setActive(false); // Halt HDDs if (headDown1DockWidget) { HDDisplay* hddWidget = dynamic_cast( headDown1DockWidget->widget() ); if (hddWidget) hddWidget->stop(); } if (headDown2DockWidget) { HDDisplay* hddWidget = dynamic_cast( headDown2DockWidget->widget() ); if (hddWidget) hddWidget->stop(); } // Halt HSI if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); if (hsi) hsi->stop(); } // Remove all dock widgets from main window QObjectList childList( this->children() ); QObjectList::iterator i; QDockWidget* dockWidget; for (i = childList.begin(); i != childList.end(); ++i) { dockWidget = dynamic_cast(*i); if (dockWidget) { // Remove dock widget from main window //this->removeDockWidget(dockWidget); dockWidget->setVisible(false); // Deletion of dockWidget would also delete all child // widgets of dockWidget // Is there a way to unset a widget from QDockWidget? } } } void MainWindow::loadSlugsView() { clearView(); // Engineer view, used in EMAV2009 // LINE CHART if (linechartWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { linechartWidget->setActive(true); centerStack->setCurrentWidget(linechartWidget); } } // 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(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // DEBUG CONSOLE if (debugConsoleDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget); debugConsoleDockWidget->show(); } // Slugs Data View if (slugsDataWidget) { addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget); slugsDataWidget->show(); } // Slugs Data View if (slugsHilSimWidget) { addDockWidget(Qt::LeftDockWidgetArea, slugsHilSimWidget); slugsHilSimWidget->show(); } } void MainWindow::loadPixhawkView() { clearView(); // Engineer view, used in EMAV2009 #ifdef QGC_OSG_ENABLED // 3D map if (_3DWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { //map3DWidget->setActive(true); centerStack->setCurrentWidget(_3DWidget); } } #endif // UAS CONTROL if (controlDockWidget) { addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget); controlDockWidget->show(); } // HORIZONTAL SITUATION INDICATOR if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); if (hsi) { hsi->start(); addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget); hsiDockWidget->show(); } } // UAS LIST if (listDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, listDockWidget); listDockWidget->show(); } // UAS STATUS if (infoDockWidget) { addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget); infoDockWidget->show(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // DEBUG CONSOLE if (debugConsoleDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget); debugConsoleDockWidget->show(); } // ONBOARD PARAMETERS if (parametersDockWidget) { addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget); parametersDockWidget->show(); } } void MainWindow::loadDataView() { clearView(); // DATAPLOT if (dataplotWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) centerStack->setCurrentWidget(dataplotWidget); } } void MainWindow::loadDataView(QString fileName) { clearView(); // DATAPLOT if (dataplotWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { centerStack->setCurrentWidget(dataplotWidget); dataplotWidget->loadFile(fileName); } } } void MainWindow::loadPilotView() { clearView(); // HEAD UP DISPLAY if (hudWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { centerStack->setCurrentWidget(hudWidget); hudWidget->start(); } } //connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*))); if (headDown1DockWidget) { HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget()); if (hdd) { addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget); headDown1DockWidget->show(); hdd->start(); } } if (headDown2DockWidget) { HDDisplay *hdd = dynamic_cast(headDown2DockWidget->widget()); if (hdd) { addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget); headDown2DockWidget->show(); hdd->start(); } } } void MainWindow::loadOperatorView() { clearView(); // MAP if (mapWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { centerStack->setCurrentWidget(mapWidget); } } // 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(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // HORIZONTAL SITUATION INDICATOR if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); if (hsi) { addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget); hsiDockWidget->show(); hsi->start(); } } // OBJECT DETECTION if (detectionDockWidget) { addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget); detectionDockWidget->show(); } // PROCESS CONTROL if (watchdogControlDockWidget) { addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget); watchdogControlDockWidget->show(); } } void MainWindow::loadGlobalOperatorView() { clearView(); // MAP if (mapWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { centerStack->setCurrentWidget(mapWidget); } } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // Slugs Data View if (slugsDataWidget) { addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget); slugsDataWidget->show(); } // Slugs Data View if (slugsPIDControlWidget) { addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget); slugsPIDControlWidget->show(); } if (slugsCamControlWidget) { addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget); slugsCamControlWidget->show(); } } void MainWindow::load3DMapView() { #ifdef QGC_OSGEARTH_ENABLED clearView(); // 3D map if (_3DMapWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { //map3DWidget->setActive(true); centerStack->setCurrentWidget(_3DMapWidget); } } // UAS CONTROL if (controlDockWidget) { addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget); controlDockWidget->show(); } // UAS LIST if (listDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, listDockWidget); listDockWidget->show(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // HORIZONTAL SITUATION INDICATOR if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); if (hsi) { hsi->start(); addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget); hsiDockWidget->show(); } } #endif } void MainWindow::loadGoogleEarthView() { #if (defined Q_OS_WIN) | (defined Q_OS_MAC) clearView(); // 3D map if (gEarthWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { centerStack->setCurrentWidget(gEarthWidget); } } // UAS CONTROL if (controlDockWidget) { addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget); controlDockWidget->show(); } // UAS LIST if (listDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, listDockWidget); listDockWidget->show(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // HORIZONTAL SITUATION INDICATOR if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); if (hsi) { hsi->start(); addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget); hsiDockWidget->show(); } } #endif } void MainWindow::load3DView() { #ifdef QGC_OSG_ENABLED clearView(); // 3D map if (_3DWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { //map3DWidget->setActive(true); centerStack->setCurrentWidget(_3DWidget); } } // UAS CONTROL if (controlDockWidget) { addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget); controlDockWidget->show(); } // UAS LIST if (listDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, listDockWidget); listDockWidget->show(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // HORIZONTAL SITUATION INDICATOR if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); if (hsi) { hsi->start(); addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget); hsiDockWidget->show(); } } #endif } void MainWindow::loadEngineerView() { clearView(); // Engineer view, used in EMAV2009 // LINE CHART if (linechartWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { linechartWidget->setActive(true); centerStack->setCurrentWidget(linechartWidget); } } // 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(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // DEBUG CONSOLE if (debugConsoleDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget); debugConsoleDockWidget->show(); } // ONBOARD PARAMETERS if (parametersDockWidget) { addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget); parametersDockWidget->show(); } // RADIO CONTROL VIEW if (rcViewDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget); rcViewDockWidget->show(); } } void MainWindow::loadMAVLinkView() { clearView(); if (protocolWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { centerStack->setCurrentWidget(protocolWidget); } } } void MainWindow::loadAllView() { clearView(); if (headDown1DockWidget) { HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget()); if (hdd) { addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget); headDown1DockWidget->show(); hdd->start(); } } if (headDown2DockWidget) { HDDisplay *hdd = dynamic_cast(headDown2DockWidget->widget()); if (hdd) { addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget); headDown2DockWidget->show(); hdd->start(); } } // 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(); } // WAYPOINT LIST if (waypointsDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); waypointsDockWidget->show(); } // DEBUG CONSOLE if (debugConsoleDockWidget) { addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget); debugConsoleDockWidget->show(); } // OBJECT DETECTION if (detectionDockWidget) { addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget); detectionDockWidget->show(); } // LINE CHART if (linechartWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { linechartWidget->setActive(true); centerStack->setCurrentWidget(linechartWidget); } } // ONBOARD PARAMETERS if (parametersDockWidget) { addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget); parametersDockWidget->show(); } } void MainWindow::loadWidgets() { //loadEngineerView(); }