Skip to content
Snippets Groups Projects
MainWindow.cc 47.2 KiB
Newer Older
  • Learn to ignore specific revisions
  • 
    void MainWindow::showCriticalMessage(const QString& title, const QString& message)
    {
        QMessageBox msgBox(MainWindow::instance());
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText(title);
        msgBox.setInformativeText(message);
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    lm's avatar
    lm committed
    void MainWindow::showInfoMessage(const QString& title, const QString& message)
    {
        QMessageBox msgBox(MainWindow::instance());
        msgBox.setIcon(QMessageBox::Information);
        msgBox.setText(title);
        msgBox.setInformativeText(message);
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
    
    
    pixhawk's avatar
    pixhawk committed
    /**
    * @brief Create all actions associated to the main window
    *
    **/
    
    pixhawk's avatar
    pixhawk committed
    {
        // 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*)));
    
    
    pixhawk's avatar
    pixhawk committed
        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()));
    
    
        connect(ui.actionPilotsView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
    
        connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
    
        connect(ui.actionOperatorsView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
    
        connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
        connect(ui.actionReloadStyle, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
    
        connect(ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
    
        connect(ui.actionDeveloper_Credits, SIGNAL(triggered()), this, SLOT(showCredits()));
    
        connect(ui.actionProject_Roadmap_2, SIGNAL(triggered()), this, SLOT(showRoadMap()));
    
        ui.actionJoystickSettings->setVisible(true);
    
        // Joystick configuration
        connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    void MainWindow::showHelp()
    {
    
        if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/users/")))
    
        {
            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
    void MainWindow::configure()
    
    pixhawk's avatar
    pixhawk committed
    {
        joystickWidget = new JoystickWidget(joystick, this);
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void MainWindow::addLink()
    
    pixhawk's avatar
    pixhawk committed
    {
        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();
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void MainWindow::addLink(LinkInterface *link)
    {
    
        LinkManager::instance()->addProtocol(link, mavlink);
    
    pixhawk's avatar
    pixhawk committed
        CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
        ui.menuNetwork->addAction(commWidget->getAction());
    
        // Special case for simulationlink
        MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
        if (sim)
        {
    
            //connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
    
    pixhawk's avatar
    pixhawk committed
            connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
        }
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void MainWindow::UASCreated(UASInterface* uas)
    
    pixhawk's avatar
    pixhawk committed
    {
    
    pixhawk's avatar
    pixhawk committed
        // Connect the UAS to the full user interface
    
    
            // The pilot view was not available on startup, enable it now
            ui.actionPilotsView->setEnabled(true);
    
    
            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)
            {
    
    pixhawk's avatar
    pixhawk committed
                DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
                if (debugConsole)
                {
                    connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
                            debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
                }
    
    
            // Health / System status indicator
    
    pixhawk's avatar
    pixhawk committed
                UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
                if (infoWidget)
                {
                    infoWidget->addUAS(uas);
                }
    
    pixhawk's avatar
    pixhawk committed
                UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
                if (listWidget)
                {
                    listWidget->addUAS(uas);
                }
    
            switch (uas->getAutopilotType())
            {
            case (MAV_AUTOPILOT_SLUGS):
                {
                    // Build Slugs Widgets
                    buildSlugsWidgets();
    
                    // Connect Slugs Widgets
                    connectSlugsWidgets();
    
                    // Arrange Slugs Centerstack
                    arrangeSlugsCenterStack();
    
                    // Connect Slugs Actions
                    connectSlugsActions();
    
                    // FIXME: This type checking might be redundant
                    //            if (slugsDataWidget) {
                    //              SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
                    //              if (dataWidget) {
                    //                SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
                    //                if (mav2) {
                    (dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget()))->addUAS(uas);
                    //                  //loadSlugsView();
                    //                  loadGlobalOperatorView();
                    //                }
                    //              }
                    //            }
                }
                break;
            default:
            case (MAV_AUTOPILOT_GENERIC):
            case (MAV_AUTOPILOT_ARDUPILOTMEGA):
            case (MAV_AUTOPILOT_PIXHAWK):
                {
                    // Build Pixhawk Widgets
                    buildPxWidgets();
    
                    // Connect Pixhawk Widgets
                    connectPxWidgets();
    
                    // Arrange Pixhawk Centerstack
                    arrangePxCenterStack();
    
                    // Connect Pixhawk Actions
                    connectPxActions();
    
                }
                break;
    
            }
    
            // Change the view only if this is the first UAS
    
            // If this is the first connected UAS, it is both created as well as
            // the currently active UAS
            if (UASManager::instance()->getActiveUAS() == uas)
            {
                qDebug() << "UPDATING THE VIEW SINCE THIS IS THE FIRST CONNECTED SYSTEM";
    
                // Load last view if setting is present
    
                if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED"))
    
                    int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt();
    
                    currentView = (VIEW_SECTIONS) view;
                    presentView();
    
    
                    // Restore the widget positions and size
                    if (settings.contains(getWindowStateKey()))
                    {
                        restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion());
                    }
    
    
                }
                else
                {
                    loadEngineerView();
                }
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    /**
     * Clears the current view completely
     */
    
    pixhawk's avatar
    pixhawk committed
    void MainWindow::clearView()
    
        // Save current state
        if (UASManager::instance()->getActiveUAS()) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion()));
        settings.setValue(getWindowGeometryKey(), saveGeometry());
        settings.sync();
    
    
        // Remove all dock widgets from main window
        QObjectList childList( this->children() );
    
    pixhawk's avatar
    pixhawk committed
    
    
        QObjectList::iterator i;
        QDockWidget* dockWidget;
        for (i = childList.begin(); i != childList.end(); ++i)
    
    pixhawk's avatar
    pixhawk committed
        {
    
            dockWidget = dynamic_cast<QDockWidget*>(*i);
            if (dockWidget)
    
    pixhawk's avatar
    pixhawk committed
            {
    
                // 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?
    
    lm's avatar
    lm committed
    {
    
        if (currentView != VIEW_ENGINEER)
        {
            clearView();
    
    lm's avatar
    lm committed
    
    
            currentView = VIEW_ENGINEER;
    
    lm's avatar
    lm committed
    
    
            presentView();
        }
    
    lm's avatar
    lm committed
    }
    
    
    lm's avatar
    lm committed
    {
    
        if (currentView != VIEW_OPERATOR)
        {
            clearView();
    
            currentView = VIEW_OPERATOR;
    
    lm's avatar
    lm committed
    
    
            presentView();
        }
    
    lm's avatar
    lm committed
    }
    
    
        if (currentView != VIEW_PILOT)
        {
            clearView();
    
            currentView = VIEW_PILOT;
    
            presentView();
        }
    
        if (currentView != VIEW_MAVLINK)
        {
            clearView();
    
    pixhawk's avatar
    pixhawk committed
    
    
            currentView = VIEW_MAVLINK;
    
            presentView();
        }
    
    lm's avatar
    lm committed
    void MainWindow::presentView()
    {
    
        // LINE CHART
    
        showTheCentralWidget(CENTRAL_LINECHART, currentView);
    
        // MAP
        showTheCentralWidget(CENTRAL_MAP, currentView);
    
    pixhawk's avatar
    pixhawk committed
    
    
        // PROTOCOL
        showTheCentralWidget(CENTRAL_PROTOCOL, currentView);
    
    pixhawk's avatar
    pixhawk committed
    
    
        // HEAD UP DISPLAY
        showTheCentralWidget(CENTRAL_HUD, currentView);
    
    pixhawk's avatar
    pixhawk committed
    
        // GOOGLE EARTH
        showTheCentralWidget(CENTRAL_GOOGLE_EARTH, currentView);
    
        // LOCAL 3D VIEW
        showTheCentralWidget(CENTRAL_3D_LOCAL, currentView);
    
        // GLOBAL 3D VIEW
        showTheCentralWidget(CENTRAL_3D_MAP, currentView);
    
    
        // DATA PLOT
        showTheCentralWidget(CENTRAL_DATA_PLOT, currentView);
    
    
    pixhawk's avatar
    pixhawk committed
    
    
        // Show docked widgets based on current view and autopilot type
    
        // UAS CONTROL
        showTheWidget(MENU_UAS_CONTROL, currentView);
    
        // UAS LIST
        showTheWidget(MENU_UAS_LIST, currentView);
    
        // WAYPOINT LIST
        showTheWidget(MENU_WAYPOINTS, currentView);
    
        // UAS STATUS
        showTheWidget(MENU_STATUS, currentView);
    
        // DETECTION
        showTheWidget(MENU_DETECTION, currentView);
    
        // DEBUG CONSOLE
        showTheWidget(MENU_DEBUG_CONSOLE, currentView);
    
        // ONBOARD PARAMETERS
        showTheWidget(MENU_PARAMETERS, currentView);
    
        // WATCHDOG
        showTheWidget(MENU_WATCHDOG, currentView);
    
        // HUD
        showTheWidget(MENU_HUD, currentView);
        if (headUpDockWidget)
        {
            HUD* tmpHud = dynamic_cast<HUD*>( headUpDockWidget->widget() );
    
            if (tmpHud)
            {
                if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HUD,currentView)).toBool())
                {
    
                    addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HUD, currentView)).toInt()),
                                  hsiDockWidget);
                    headUpDockWidget->show();
    
                    headUpDockWidget->hide();
                }
    
        // RC View
        showTheWidget(MENU_RC_VIEW, currentView);
    
        // SLUGS DATA
        showTheWidget(MENU_SLUGS_DATA, currentView);
    
        // SLUGS PID
        showTheWidget(MENU_SLUGS_PID, currentView);
    
        // SLUGS HIL
        showTheWidget(MENU_SLUGS_HIL, currentView);
    
        // SLUGS CAMERA
        showTheWidget(MENU_SLUGS_CAMERA, currentView);
    
        // HORIZONTAL SITUATION INDICATOR
        showTheWidget(MENU_HSI, currentView);
    
        // HEAD DOWN 1
        showTheWidget(MENU_HDD_1, currentView);
    
        // HEAD DOWN 2
        showTheWidget(MENU_HDD_2, currentView);
    
        this->show();
    
    void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view)
    {
        bool tempVisible;
        QWidget* tempWidget = dockWidgets[centralWidget];
    
        tempVisible =  settings.value(buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view), false).toBool();
    
        qDebug() << buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view) << tempVisible;
        if (toolsMenuActions[centralWidget])
    
            toolsMenuActions[centralWidget]->setChecked(tempVisible);
    
        if (centerStack && tempWidget && tempVisible)
    
            centerStack->setCurrentWidget(tempWidget);
    
    void MainWindow::loadDataView(QString fileName)
    {
    
        clearView();
    
        // Set data plot in settings as current widget and then run usual update procedure
        QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(CENTRAL_DATA_PLOT), currentView);
        settings.setValue(chKey,true);
    
        presentView();
    
        // Plot is now selected, now load data from file
        if (dataplotWidget)
    
            dataplotWidget->loadFile(fileName);
    
    //        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
    //        if (centerStack)
    //        {
    //            centerStack->setCurrentWidget(dataplotWidget);
    //            dataplotWidget->loadFile(fileName);
    //        }
    //    }