Skip to content
MainWindow.cc 49.3 KiB
Newer Older
    }
    if (headDown2DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
            headDown2DockWidget->show();
            hdd->start();
        }
    }
pixhawk's avatar
pixhawk committed
    this->show();
}

pixhawk's avatar
pixhawk committed
void MainWindow::loadOperatorView()
pixhawk's avatar
pixhawk committed
{
    clearView();

    if (mapWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(mapWidget);
        }
    }
pixhawk's avatar
pixhawk committed

    // UAS CONTROL
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
pixhawk's avatar
pixhawk committed

    // UAS LIST
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
pixhawk's avatar
pixhawk committed

    // UAS STATUS
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
pixhawk's avatar
pixhawk committed

    // WAYPOINT LIST
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
pixhawk's avatar
pixhawk committed

lm's avatar
lm committed
    // HORIZONTAL SITUATION INDICATOR
    if (hsiDockWidget)
    {
        HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
        if (hsi)
        {
            addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
            hsiDockWidget->show();
            hsi->start();
        }
    }
pixhawk's avatar
pixhawk committed

    // OBJECT DETECTION
    if (detectionDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
        detectionDockWidget->show();
    }
pixhawk's avatar
pixhawk committed

pixhawk's avatar
pixhawk committed
    // PROCESS CONTROL
    if (watchdogControlDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
        watchdogControlDockWidget->show();
    }

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

    if (mapWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            centerStack->setCurrentWidget(mapWidget);
        }
    }
tecnosapiens's avatar
tecnosapiens committed
    // WAYPOINT LIST
    if (waypointsDockWidget)
tecnosapiens's avatar
tecnosapiens committed
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
tecnosapiens's avatar
tecnosapiens committed
    // Slugs Data View
    if (slugsDataWidget)
tecnosapiens's avatar
tecnosapiens committed
        addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget);
        slugsDataWidget->show();
    if (slugsPIDControlWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget);
        slugsPIDControlWidget->show();
    }

    if (slugsCamControlWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
        slugsCamControlWidget->show();
    }

pixhawk's avatar
pixhawk committed
}

void MainWindow::load3DMapView()
pixhawk's avatar
pixhawk committed
{
pixhawk's avatar
pixhawk committed

            if (_3DMapWidget)
            {
                QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
                if (centerStack)
                {
                    //map3DWidget->setActive(true);
                    centerStack->setCurrentWidget(_3DMapWidget);
pixhawk's avatar
pixhawk committed

            // UAS CONTROL
            if (controlDockWidget)
            {
                addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
                controlDockWidget->show();
            }
pixhawk's avatar
pixhawk committed

            // 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<HSIDisplay*>( hsiDockWidget->widget() );
                if (hsi)
                {
                    hsi->start();
                    addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
                    hsiDockWidget->show();
                }
            }
#endif
            this->show();
pixhawk's avatar
pixhawk committed
void MainWindow::loadGoogleEarthView()
{
    #if (defined Q_OS_WIN) | (defined Q_OS_MAC)
pixhawk's avatar
pixhawk committed
            clearView();

            // 3D map
            if (gEarthWidget)
            {
                QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(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<HSIDisplay*>( hsiDockWidget->widget() );
                if (hsi)
                {
                    hsi->start();
                    addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
                    hsiDockWidget->show();
                }
            }
void MainWindow::load3DView()
pixhawk's avatar
pixhawk committed
{
pixhawk's avatar
pixhawk committed

            {
                QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
                if (centerStack)
                {
                    //map3DWidget->setActive(true);
pixhawk's avatar
pixhawk committed

            // UAS CONTROL
            if (controlDockWidget)
            {
                addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
                controlDockWidget->show();
            }
pixhawk's avatar
pixhawk committed

            // 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<HSIDisplay*>( hsiDockWidget->widget() );
                if (hsi)
                {
                    hsi->start();
                    addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
                    hsiDockWidget->show();
                }
            }
pixhawk's avatar
pixhawk committed

pixhawk's avatar
pixhawk committed
void MainWindow::loadEngineerView()
pixhawk's avatar
pixhawk committed
{
    clearView();
    // Engineer view, used in EMAV2009

    switch (UASManager::instance()->getActiveUAS()->getAutopilotType()){
      case (MAV_AUTOPILOT_GENERIC):
      case (MAV_AUTOPILOT_ARDUPILOTMEGA):
      case (MAV_AUTOPILOT_PIXHAWK):
        loadPixhawkEngineerView();
      break;
pixhawk's avatar
pixhawk committed

      case (MAV_AUTOPILOT_SLUGS):
        loadSlugsEngineerView();
      break;
pixhawk's avatar
pixhawk committed
    this->show();
}


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

    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();
        }
    }
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
    if (debugConsoleDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
        debugConsoleDockWidget->show();
    }
    if (detectionDockWidget)
    {
pixhawk's avatar
pixhawk committed
        addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
        detectionDockWidget->show();
    if (linechartWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            linechartWidget->setActive(true);
            centerStack->setCurrentWidget(linechartWidget);
        }
    }
    if (parametersDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
        parametersDockWidget->show();
    }
pixhawk's avatar
pixhawk committed
void MainWindow::loadWidgets()
pixhawk's avatar
pixhawk committed
{
    //loadOperatorView();
    loadEngineerView();
pixhawk's avatar
pixhawk committed
    //loadPilotView();
}


/*
 ==================================
 ========== ATTIC =================
 ==================================

void MainWindow::buildCommonWidgets()
{
    //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) );

    listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
    listDockWidget->setWidget( new UASListWidget(this) );

    waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
    waypointsDockWidget->setWidget( new WaypointList(this, NULL) );

    infoDockWidget = new QDockWidget(tr("Status Details"), this);
    infoDockWidget->setWidget( new UASInfoWidget(this) );

    detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
    detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );

    debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
    debugConsoleDockWidget->setWidget( new DebugConsole(this) );

    parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
    parametersDockWidget->setWidget( new ParameterInterface(this) );

    watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
    watchdogControlDockWidget->setWidget( new WatchdogControl(this) );

    hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
    hsiDockWidget->setWidget( new HSIDisplay(this) );

    headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
    headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );

    headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
    headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );

    rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
    rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );

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

    // Dialogue widgets
    //FIXME: free memory in destructor
    joystick    = new JoystickInput();

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

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

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

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

}

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::arrangeCommonCenterStack()
{

    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::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())

}

*/