Skip to content
MainWindow.cc 48.8 KiB
Newer Older
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

pixhawk's avatar
pixhawk committed
void MainWindow::configure()
pixhawk's avatar
pixhawk committed
{
    if (!joystickWidget) {
        if (!joystick->isRunning()) {
            joystick->start();
        }
        joystickWidget = new JoystickWidget(joystick);
    }
    joystickWidget->show();
pixhawk's avatar
pixhawk committed
}

void MainWindow::showSettings()
{
    QGCSettingsWidget* settings = new QGCSettingsWidget(this);
    settings->show();
}

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()->add(link);
pixhawk's avatar
pixhawk committed
    LinkManager::instance()->addProtocol(link, mavlink);

    // Go fishing for this link's configuration window
    QList<QAction*> actions = ui.menuNetwork->actions();
pixhawk's avatar
pixhawk committed

lm's avatar
lm committed
    foreach (QAction* act, actions)
    {
        if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link))
        {
pixhawk's avatar
pixhawk committed
}

pixhawk's avatar
pixhawk committed
void MainWindow::addLink(LinkInterface *link)
{
    // IMPORTANT! KEEP THESE TWO LINES
    // THEY MAKE SURE THE LINK IS PROPERLY REGISTERED
    // BEFORE LINKING THE UI AGAINST IT
    // Register (does nothing if already registered)
    LinkManager::instance()->add(link);
    LinkManager::instance()->addProtocol(link, mavlink);
    // Go fishing for this link's configuration window
    QList<QAction*> actions = ui.menuNetwork->actions();
    foreach (QAction* act, actions) {
        if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link)) {
            found = true;
        }
    }

    UDPLink* udp = dynamic_cast<UDPLink*>(link);
    if (!found || udp) {
        CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
        QAction* action = commWidget->getAction();
        ui.menuNetwork->addAction(action);

        // Error handling
        connect(link, SIGNAL(communicationError(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection);
        // Special case for simulationlink
        MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
            //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::setActiveUAS(UASInterface* uas)
{
    // Enable and rename menu
    ui.menuUnmanned_System->setTitle(uas->getUASName());
    if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true);
}

void MainWindow::UASSpecsChanged(int uas)
{
    UASInterface* activeUAS = UASManager::instance()->getActiveUAS();
    if (activeUAS) {
        if (activeUAS->getUASID() == uas) {
            ui.menuUnmanned_System->setTitle(activeUAS->getUASName());
        }
    }
}

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

lm's avatar
lm committed
    if (uas != NULL)
    {
        // The pilot, operator and engineer views were not available on startup, enable them now
        ui.actionPilotsView->setEnabled(true);
        ui.actionOperatorsView->setEnabled(true);
        ui.actionEngineersView->setEnabled(true);
        // The UAS actions are not enabled without connection to system
        ui.actionLiftoff->setEnabled(true);
        ui.actionLand->setEnabled(true);
        ui.actionEmergency_Kill->setEnabled(true);
        ui.actionEmergency_Land->setEnabled(true);
        ui.actionShutdownMAV->setEnabled(true);
        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;
        }

        QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems);
        connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater()));
        connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
        connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int)));

        ui.menuConnected_Systems->addAction(uasAction);

        // FIXME Should be not inside the mainwindow
        if (debugConsoleDockWidget) {
pixhawk's avatar
pixhawk committed
            DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
            if (debugConsole) {
pixhawk's avatar
pixhawk committed
                connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
                        debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
            }

        // Health / System status indicator
        if (infoDockWidget) {
pixhawk's avatar
pixhawk committed
            UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
            if (infoWidget) {
pixhawk's avatar
pixhawk committed
                infoWidget->addUAS(uas);
            }
lm's avatar
lm committed
        if (listDockWidget)
        {
pixhawk's avatar
pixhawk committed
            UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
lm's avatar
lm committed
            if (listWidget)
            {
pixhawk's avatar
pixhawk committed
                listWidget->addUAS(uas);
            }
        // Line chart
        if (!linechartWidget)
lm's avatar
lm committed
        {
LM's avatar
LM committed
            linechartWidget = new Linecharts(this);
            //linechartWidget FIXME
            addCentralWidget(linechartWidget, tr("Realtime Plot"));
LM's avatar
LM committed
        // Load default custom widgets for this autopilot type
lm's avatar
lm committed
        loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName());
lm's avatar
lm committed
        if (uas->getAutopilotType() == MAV_AUTOPILOT_PIXHAWK)
        {
            // Dock widgets
            if (!detectionDockWidget)
            {
                detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
                detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
                detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET");
                addTool(detectionDockWidget, tr("Object Recognition"), Qt::RightDockWidgetArea);
            }

            if (!watchdogControlDockWidget) {
                watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
                watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
                watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET");
                addTool(watchdogControlDockWidget, tr("Process Control"), Qt::BottomDockWidgetArea);
            }
        }

        // 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()->getUASList().size() == 1)
        {
            // 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();
                switch (view) {
                case VIEW_ENGINEER:
                    loadEngineerView();
                    break;
                case VIEW_MAVLINK:
                    loadMAVLinkView();
                    break;
                case VIEW_PILOT:
                    loadPilotView();
                    break;
                case VIEW_UNCONNECTED:
                    loadUnconnectedView();
                    break;
                case VIEW_OPERATOR:
                default:
                    loadOperatorView();
                    break;
                loadOperatorView();

    if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
lm's avatar
lm committed

LM's avatar
LM committed
    if (settings.contains(getWindowGeometryKey()))
    {
        restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray());
    }
pixhawk's avatar
pixhawk committed
}

 * Stores the current view state
void MainWindow::storeViewState()
pixhawk's avatar
pixhawk committed
    if (!aboutToCloseFlag)
lm's avatar
lm committed
    {
pixhawk's avatar
pixhawk committed
        // Save current state
        settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion()));
        settings.setValue(getWindowStateKey()+"CENTER_WIDGET", centerStack->currentIndex());
        // Although we want save the state of the window, we do not want to change the top-leve state (minimized, maximized, etc)
        // therefore this state is stored here and restored after applying the rest of the settings in the new
        // perspective.
        windowStateVal = this->windowState();
        settings.setValue(getWindowGeometryKey(), saveGeometry());
void MainWindow::loadViewState()
{
    // Restore center stack state
lm's avatar
lm committed
    int index = settings.value(getWindowStateKey()+"CENTER_WIDGET", -1).toInt();
LM's avatar
LM committed
    // The offline plot view is usually the consequence of a logging run, always show the realtime view first
    if (centerStack->indexOf(dataplotWidget) == index)
    {
        // Rewrite to realtime plot
        index = centerStack->indexOf(linechartWidget);
    }
pixhawk's avatar
pixhawk committed

lm's avatar
lm committed
    if (index != -1)
    {
        centerStack->setCurrentIndex(index);
    }
    else
    {
        // Load defaults
        switch (currentView)
        {
        case VIEW_ENGINEER:
            centerStack->setCurrentWidget(linechartWidget);
lm's avatar
lm committed
            controlDockWidget->hide();
            listDockWidget->hide();
            waypointsDockWidget->hide();
            infoDockWidget->hide();
            debugConsoleDockWidget->show();
            logPlayerDockWidget->show();
            mavlinkInspectorWidget->show();
            parametersDockWidget->show();
            hsiDockWidget->hide();
            headDown1DockWidget->hide();
            headDown2DockWidget->hide();
            rcViewDockWidget->hide();
            headUpDockWidget->hide();
            video1DockWidget->hide();
            video2DockWidget->hide();
lm's avatar
lm committed
            break;
        case VIEW_PILOT:
            centerStack->setCurrentWidget(hudWidget);
lm's avatar
lm committed
            controlDockWidget->hide();
            listDockWidget->hide();
            waypointsDockWidget->hide();
            infoDockWidget->hide();
            debugConsoleDockWidget->hide();
            logPlayerDockWidget->hide();
            mavlinkInspectorWidget->hide();
            parametersDockWidget->hide();
            hsiDockWidget->show();
            headDown1DockWidget->show();
            headDown2DockWidget->show();
            rcViewDockWidget->hide();
            headUpDockWidget->hide();
            video1DockWidget->show();
            video2DockWidget->hide();
lm's avatar
lm committed
            break;
        case VIEW_MAVLINK:
            centerStack->setCurrentWidget(protocolWidget);
lm's avatar
lm committed
            controlDockWidget->hide();
            listDockWidget->hide();
            waypointsDockWidget->hide();
            infoDockWidget->hide();
            debugConsoleDockWidget->hide();
            logPlayerDockWidget->hide();
            mavlinkInspectorWidget->hide();
            parametersDockWidget->hide();
            hsiDockWidget->hide();
            headDown1DockWidget->hide();
            headDown2DockWidget->hide();
            rcViewDockWidget->hide();
            headUpDockWidget->hide();
            video1DockWidget->hide();
            video2DockWidget->hide();
lm's avatar
lm committed
            break;
        case VIEW_OPERATOR:
        case VIEW_UNCONNECTED:
        case VIEW_FULL:
        default:
            centerStack->setCurrentWidget(mapWidget);
lm's avatar
lm committed
            controlDockWidget->show();
            listDockWidget->show();
            waypointsDockWidget->show();
            infoDockWidget->show();
            debugConsoleDockWidget->show();
            logPlayerDockWidget->show();
            mavlinkInspectorWidget->show();
            parametersDockWidget->hide();
            hsiDockWidget->show();
            headDown1DockWidget->hide();
            headDown2DockWidget->hide();
            rcViewDockWidget->hide();
            headUpDockWidget->show();
            video1DockWidget->hide();
            video2DockWidget->hide();
lm's avatar
lm committed
            break;
pixhawk's avatar
pixhawk committed
        }
    }

    // Restore the widget positions and size
    if (settings.contains(getWindowStateKey()))
    {
        restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion());
pixhawk's avatar
pixhawk committed
    }
}

lm's avatar
lm committed
{
    if (currentView != VIEW_ENGINEER) {
        currentView = VIEW_ENGINEER;
        ui.actionEngineersView->setChecked(true);
lm's avatar
lm committed
}

lm's avatar
lm committed
{
    if (currentView != VIEW_OPERATOR) {
        currentView = VIEW_OPERATOR;
        ui.actionOperatorsView->setChecked(true);
lm's avatar
lm committed

void MainWindow::loadUnconnectedView()
{
    if (currentView != VIEW_UNCONNECTED)
    {
        storeViewState();
        currentView = VIEW_UNCONNECTED;
        ui.actionUnconnectedView->setChecked(true);
lm's avatar
lm committed
}

    if (currentView != VIEW_PILOT)
    {
        storeViewState();
        currentView = VIEW_PILOT;
        ui.actionPilotsView->setChecked(true);
    if (currentView != VIEW_MAVLINK)
    {
        storeViewState();
        currentView = VIEW_MAVLINK;
        ui.actionMavlinkView->setChecked(true);
void MainWindow::loadDataView(QString fileName)
{
    // 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);
oberion's avatar
oberion committed
QList<QAction*> MainWindow::listLinkMenuActions(void)
{
lm's avatar
lm committed
    return ui.menuNetwork->actions();