diff --git a/src/configuration.h b/src/configuration.h index c91fae7efbcffd00cab6f9ef7ecefedc5c0fa230..e06ad87f0adc6ca998d39875662470d3fa29bdc3 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -17,14 +17,14 @@ #define WITH_TEXT_TO_SPEECH 1 #define QGC_APPLICATION_NAME "QGroundControl" -#define QGC_APPLICATION_VERSION "v. 0.8.1 (Alpha)" +#define QGC_APPLICATION_VERSION "v. 0.8.3 (Alpha)" namespace QGC { const QString APPNAME = "QGROUNDCONTROL"; const QString COMPANYNAME = "OPENMAV"; - const int APPLICATIONVERSION = 80; // 0.8.0 + const int APPLICATIONVERSION = 83; // 0.8.0 } #endif // CONFIGURATION_H diff --git a/src/ui/HDDisplay.cc b/src/ui/HDDisplay.cc index fc365fd162492dd77f27be60241478f02cfe8057..d598f458fdafa244affd911148dabac7130a8d34 100644 --- a/src/ui/HDDisplay.cc +++ b/src/ui/HDDisplay.cc @@ -152,7 +152,7 @@ HDDisplay::~HDDisplay() QSize HDDisplay::sizeHint() const { - return QSize(400, 400.0f*(vwidth/vheight)*1.1f); + return QSize(400, 400.0f*(vwidth/vheight)*1.2f); } void HDDisplay::enableGLRendering(bool enable) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index eed18282961a5ea4d8a15ef9c26749e07f5d8852..566b57fe769b088b2d77e806101b3854c7c1b381 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -64,7 +64,7 @@ MainWindow* MainWindow::instance() MainWindow::MainWindow(QWidget *parent): QMainWindow(parent), toolsMenuActions(), - currentView(VIEW_ENGINEER), + currentView(VIEW_UNCONNECTED), aboutToCloseFlag(false), changingViewsFlag(false) { @@ -82,47 +82,17 @@ MainWindow::MainWindow(QWidget *parent): } else { - if (settings.value("CURRENT_VIEW", VIEW_PILOT) != VIEW_PILOT) + // LOAD THE LAST VIEW + VIEW_SECTIONS currentViewCandidate = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", currentView).toInt(); + if (currentViewCandidate != VIEW_ENGINEER && + currentViewCandidate != VIEW_OPERATOR && + currentViewCandidate != VIEW_PILOT) { - currentView = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", currentView).toInt(); + currentView = currentViewCandidate; } } - // Check if the settings exist, instantiate defaults if necessary - - // OPERATOR VIEW DEFAULT - QString centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_MAP, VIEW_OPERATOR); - if (!settings.contains(centralKey)) - { - settings.setValue(centralKey,true); - } - - // ENGINEER VIEW DEFAULT - centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_LINECHART, VIEW_ENGINEER); - if (!settings.contains(centralKey)) - { - settings.setValue(centralKey,true); - } - - // MAVLINK VIEW DEFAULT - centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_PROTOCOL, VIEW_MAVLINK); - if (!settings.contains(centralKey)) - { - settings.setValue(centralKey,true); - } - - // PILOT VIEW DEFAULT - centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_HUD, VIEW_PILOT); - if (!settings.contains(centralKey)) - { - settings.setValue(centralKey,true); - } - - QString listKey = buildMenuKey(SUB_SECTION_CHECKED, MENU_UAS_LIST, currentView); - if (!settings.contains(listKey)) - { - settings.setValue(listKey, true); - } + setDefaultSettingsForAp(); settings.sync(); @@ -138,6 +108,7 @@ MainWindow::MainWindow(QWidget *parent): perspectives->addAction(ui.actionMavlinkView); perspectives->addAction(ui.actionPilotsView); perspectives->addAction(ui.actionOperatorsView); + perspectives->addAction(ui.actionUnconnectedView); perspectives->setExclusive(true); // Mark the right one as selected @@ -145,9 +116,13 @@ MainWindow::MainWindow(QWidget *parent): if (currentView == VIEW_MAVLINK) ui.actionMavlinkView->setChecked(true); if (currentView == VIEW_PILOT) ui.actionPilotsView->setChecked(true); if (currentView == VIEW_OPERATOR) ui.actionOperatorsView->setChecked(true); + if (currentView == VIEW_UNCONNECTED) ui.actionUnconnectedView->setChecked(true); - // The pilot view is not available on startup + // The pilot, engineer and operator view are not available on startup + // since they only make sense with a system connected. ui.actionPilotsView->setEnabled(false); + ui.actionOperatorsView->setEnabled(false); + ui.actionEngineersView->setEnabled(false); buildCommonWidgets(); @@ -217,6 +192,54 @@ MainWindow::~MainWindow() } +/** + * Set default settings for this AP type. + */ +void MainWindow::setDefaultSettingsForAp() +{ + // Check if the settings exist, instantiate defaults if necessary + + // UNCONNECTED VIEW DEFAULT + QString centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_MAP, VIEW_UNCONNECTED); + if (!settings.contains(centralKey)) + { + settings.setValue(centralKey,true); + } + + // OPERATOR VIEW DEFAULT + centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_MAP, VIEW_OPERATOR); + if (!settings.contains(centralKey)) + { + settings.setValue(centralKey,true); + + // ENABLE UAS LIST + settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_UAS_LIST,VIEW_OPERATOR), true); + // ENABLE COMMUNICATION CONSOLE + settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_DEBUG_CONSOLE,VIEW_OPERATOR), true); + } + + // ENGINEER VIEW DEFAULT + centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_LINECHART, VIEW_ENGINEER); + if (!settings.contains(centralKey)) + { + settings.setValue(centralKey,true); + } + + // MAVLINK VIEW DEFAULT + centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_PROTOCOL, VIEW_MAVLINK); + if (!settings.contains(centralKey)) + { + settings.setValue(centralKey,true); + } + + // PILOT VIEW DEFAULT + centralKey = buildMenuKey(SUB_SECTION_CHECKED, CENTRAL_HUD, VIEW_PILOT); + if (!settings.contains(centralKey)) + { + settings.setValue(centralKey,true); + } +} + void MainWindow::resizeEvent(QResizeEvent * event) { Q_UNUSED(event); @@ -289,7 +312,7 @@ void MainWindow::buildCommonWidgets() controlDockWidget = new QDockWidget(tr("Control"), this); controlDockWidget->setObjectName("UNMANNED_SYSTEM_CONTROL_DOCKWIDGET"); controlDockWidget->setWidget( new UASControlWidget(this) ); - addToToolsMenu (controlDockWidget, tr("Control"), SLOT(showToolWidget()), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea); + addToToolsMenu (controlDockWidget, tr("Control"), SLOT(showToolWidget(bool)), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea); } if (!listDockWidget) @@ -297,7 +320,7 @@ void MainWindow::buildCommonWidgets() listDockWidget = new QDockWidget(tr("Unmanned Systems"), this); listDockWidget->setWidget( new UASListWidget(this) ); listDockWidget->setObjectName("UNMANNED_SYSTEMS_LIST_DOCKWIDGET"); - addToToolsMenu (listDockWidget, tr("Unmanned Systems"), SLOT(showToolWidget()), MENU_UAS_LIST, Qt::RightDockWidgetArea); + addToToolsMenu (listDockWidget, tr("Unmanned Systems"), SLOT(showToolWidget(bool)), MENU_UAS_LIST, Qt::RightDockWidgetArea); } if (!waypointsDockWidget) @@ -305,7 +328,7 @@ void MainWindow::buildCommonWidgets() waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this); waypointsDockWidget->setWidget( new WaypointList(this, NULL) ); waypointsDockWidget->setObjectName("WAYPOINT_LIST_DOCKWIDGET"); - addToToolsMenu (waypointsDockWidget, tr("Waypoints List"), SLOT(showToolWidget()), MENU_WAYPOINTS, Qt::BottomDockWidgetArea); + addToToolsMenu (waypointsDockWidget, tr("Waypoints List"), SLOT(showToolWidget(bool)), MENU_WAYPOINTS, Qt::BottomDockWidgetArea); } if (!infoDockWidget) @@ -313,7 +336,7 @@ void MainWindow::buildCommonWidgets() infoDockWidget = new QDockWidget(tr("Status Details"), this); infoDockWidget->setWidget( new UASInfoWidget(this) ); infoDockWidget->setObjectName("UAS_STATUS_DETAILS_DOCKWIDGET"); - addToToolsMenu (infoDockWidget, tr("Status Details"), SLOT(showToolWidget()), MENU_STATUS, Qt::RightDockWidgetArea); + addToToolsMenu (infoDockWidget, tr("Status Details"), SLOT(showToolWidget(bool)), MENU_STATUS, Qt::RightDockWidgetArea); } if (!debugConsoleDockWidget) @@ -321,7 +344,7 @@ void MainWindow::buildCommonWidgets() debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this); debugConsoleDockWidget->setWidget( new DebugConsole(this) ); debugConsoleDockWidget->setObjectName("COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET"); - addToToolsMenu (debugConsoleDockWidget, tr("Communication Console"), SLOT(showToolWidget()), MENU_DEBUG_CONSOLE, Qt::BottomDockWidgetArea); + addToToolsMenu (debugConsoleDockWidget, tr("Communication Console"), SLOT(showToolWidget(bool)), MENU_DEBUG_CONSOLE, Qt::BottomDockWidgetArea); } if (!logPlayerDockWidget) @@ -329,13 +352,13 @@ void MainWindow::buildCommonWidgets() logPlayerDockWidget = new QDockWidget(tr("MAVLink Log Player"), this); logPlayerDockWidget->setWidget( new QGCMAVLinkLogPlayer(mavlink, this) ); logPlayerDockWidget->setObjectName("MAVLINK_LOG_PLAYER_DOCKWIDGET"); - addToToolsMenu(logPlayerDockWidget, tr("MAVLink Log Replay"), SLOT(showToolWidget()), MENU_MAVLINK_LOG_PLAYER, Qt::RightDockWidgetArea); + addToToolsMenu(logPlayerDockWidget, tr("MAVLink Log Replay"), SLOT(showToolWidget(bool)), MENU_MAVLINK_LOG_PLAYER, Qt::RightDockWidgetArea); } // Center widgets if (!mapWidget) { - mapWidget = new MapWidget(this); + mapWidget = new MapWidget(this); addToCentralWidgetsMenu (mapWidget, "Maps", SLOT(showCentralWidget()),CENTRAL_MAP); } @@ -350,7 +373,7 @@ void MainWindow::buildCommonWidgets() { slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this); slugsHilSimWidget->setWidget( new SlugsHilSim(this)); - addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea); + addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea); } //TODO temporaly debug @@ -358,7 +381,7 @@ void MainWindow::buildCommonWidgets() { slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this); slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this)); - addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea); + addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget(bool)), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea); } if (!dataplotWidget) { @@ -437,7 +460,7 @@ void MainWindow::buildPxWidgets() detectionDockWidget = new QDockWidget(tr("Object Recognition"), this); detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) ); detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET"); - addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget()), MENU_DETECTION, Qt::RightDockWidgetArea); + addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget(bool)), MENU_DETECTION, Qt::RightDockWidgetArea); } if (!parametersDockWidget) @@ -445,7 +468,7 @@ void MainWindow::buildPxWidgets() parametersDockWidget = new QDockWidget(tr("Calibration and Onboard Parameters"), this); parametersDockWidget->setWidget( new ParameterInterface(this) ); parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET"); - addToToolsMenu (parametersDockWidget, tr("Calibration and Parameters"), SLOT(showToolWidget()), MENU_PARAMETERS, Qt::RightDockWidgetArea); + addToToolsMenu (parametersDockWidget, tr("Calibration and Parameters"), SLOT(showToolWidget(bool)), MENU_PARAMETERS, Qt::RightDockWidgetArea); } if (!watchdogControlDockWidget) @@ -453,7 +476,7 @@ void MainWindow::buildPxWidgets() watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this); watchdogControlDockWidget->setWidget( new WatchdogControl(this) ); watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET"); - addToToolsMenu (watchdogControlDockWidget, tr("Process Control"), SLOT(showToolWidget()), MENU_WATCHDOG, Qt::BottomDockWidgetArea); + addToToolsMenu (watchdogControlDockWidget, tr("Process Control"), SLOT(showToolWidget(bool)), MENU_WATCHDOG, Qt::BottomDockWidgetArea); } if (!hsiDockWidget) @@ -461,7 +484,7 @@ void MainWindow::buildPxWidgets() hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this); hsiDockWidget->setWidget( new HSIDisplay(this) ); hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET"); - addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget()), MENU_HSI, Qt::BottomDockWidgetArea); + addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget(bool)), MENU_HSI, Qt::BottomDockWidgetArea); } if (!headDown1DockWidget) @@ -469,7 +492,7 @@ void MainWindow::buildPxWidgets() headDown1DockWidget = new QDockWidget(tr("Flight Display"), this); headDown1DockWidget->setWidget( new HDDisplay(acceptList, "Flight Display", this) ); headDown1DockWidget->setObjectName("HEAD_DOWN_DISPLAY_1_DOCK_WIDGET"); - addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea); + addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget(bool)), MENU_HDD_1, Qt::RightDockWidgetArea); } if (!headDown2DockWidget) @@ -477,7 +500,7 @@ void MainWindow::buildPxWidgets() headDown2DockWidget = new QDockWidget(tr("Payload Status"), this); headDown2DockWidget->setWidget( new HDDisplay(acceptList2, "Payload Status", this) ); headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET"); - addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea); + addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget(bool)), MENU_HDD_2, Qt::RightDockWidgetArea); } if (!rcViewDockWidget) @@ -485,7 +508,7 @@ void MainWindow::buildPxWidgets() rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); rcViewDockWidget->setObjectName("RADIO_CONTROL_CHANNELS_DOCK_WIDGET"); - addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea); + addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget(bool)), MENU_RC_VIEW, Qt::BottomDockWidgetArea); } if (!headUpDockWidget) @@ -493,7 +516,7 @@ void MainWindow::buildPxWidgets() headUpDockWidget = new QDockWidget(tr("HUD"), this); headUpDockWidget->setWidget( new HUD(320, 240, this)); headUpDockWidget->setObjectName("HEAD_UP_DISPLAY_DOCK_WIDGET"); - addToToolsMenu (headUpDockWidget, tr("Control Indicator"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea); + addToToolsMenu (headUpDockWidget, tr("Control Indicator"), SLOT(showToolWidget(bool)), MENU_HUD, Qt::LeftDockWidgetArea); } if (!video1DockWidget) @@ -505,7 +528,7 @@ void MainWindow::buildPxWidgets() // FIXME select video stream as well video1DockWidget->setWidget(video1); video1DockWidget->setObjectName("VIDEO_STREAM_1_DOCK_WIDGET"); - addToToolsMenu (video1DockWidget, tr("Video Stream 1"), SLOT(showToolWidget()), MENU_VIDEO_STREAM_1, Qt::LeftDockWidgetArea); + addToToolsMenu (video1DockWidget, tr("Video Stream 1"), SLOT(showToolWidget(bool)), MENU_VIDEO_STREAM_1, Qt::LeftDockWidgetArea); } if (!video2DockWidget) @@ -517,7 +540,7 @@ void MainWindow::buildPxWidgets() // FIXME select video stream as well video2DockWidget->setWidget(video2); video2DockWidget->setObjectName("VIDEO_STREAM_2_DOCK_WIDGET"); - addToToolsMenu (video2DockWidget, tr("Video Stream 2"), SLOT(showToolWidget()), MENU_VIDEO_STREAM_2, Qt::LeftDockWidgetArea); + addToToolsMenu (video2DockWidget, tr("Video Stream 2"), SLOT(showToolWidget(bool)), MENU_VIDEO_STREAM_2, Qt::LeftDockWidgetArea); } // Dialogue widgets @@ -538,7 +561,7 @@ void MainWindow::buildSlugsWidgets() headUpDockWidget = new QDockWidget(tr("Control Indicator"), this); headUpDockWidget->setWidget( new HUD(320, 240, this)); headUpDockWidget->setObjectName("HEAD_UP_DISPLAY_DOCK_WIDGET"); - addToToolsMenu (headUpDockWidget, tr("HUD"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea); + addToToolsMenu (headUpDockWidget, tr("HUD"), SLOT(showToolWidget(bool)), MENU_HUD, Qt::LeftDockWidgetArea); } if (!rcViewDockWidget) @@ -546,7 +569,7 @@ void MainWindow::buildSlugsWidgets() rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); rcViewDockWidget->setObjectName("RADIO_CONTROL_CHANNELS_DOCK_WIDGET"); - addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea); + addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget(bool)), MENU_RC_VIEW, Qt::BottomDockWidgetArea); } if (!slugsDataWidget) @@ -555,7 +578,7 @@ void MainWindow::buildSlugsWidgets() slugsDataWidget = new QDockWidget(tr("Slugs Data"), this); slugsDataWidget->setWidget( new SlugsDataSensorView(this)); slugsDataWidget->setObjectName("SLUGS_DATA_DOCK_WIDGET"); - addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea); + addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget(bool)), MENU_SLUGS_DATA, Qt::RightDockWidgetArea); } if (!slugsPIDControlWidget) @@ -563,7 +586,7 @@ void MainWindow::buildSlugsWidgets() slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this); slugsPIDControlWidget->setWidget(new SlugsPIDControl(this)); slugsPIDControlWidget->setObjectName("SLUGS_PID_CONTROL_DOCK_WIDGET"); - addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea); + addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_PID, Qt::LeftDockWidgetArea); } if (!slugsHilSimWidget) @@ -571,7 +594,7 @@ void MainWindow::buildSlugsWidgets() slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this); slugsHilSimWidget->setWidget( new SlugsHilSim(this)); slugsHilSimWidget->setObjectName("SLUGS_HIL_SIM_DOCK_WIDGET"); - addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea); + addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea); } if (!slugsCamControlWidget) @@ -579,7 +602,7 @@ void MainWindow::buildSlugsWidgets() slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this); slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this)); slugsCamControlWidget->setObjectName("SLUGS_CAM_CONTROL_DOCK_WIDGET"); - addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea); + addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget(bool)), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea); } } @@ -592,15 +615,17 @@ void MainWindow::addToCentralWidgetsMenu ( QWidget* widget, QAction* tempAction; - // Add the separator that will separate tools from central Widgets - if (!toolsMenuActions[CENTRAL_SEPARATOR]) - { - tempAction = ui.menuTools->addSeparator(); - toolsMenuActions[CENTRAL_SEPARATOR] = tempAction; - tempAction->setData(CENTRAL_SEPARATOR); - } +// Not needed any more - separate menu now available - tempAction = ui.menuTools->addAction(title); +// // Add the separator that will separate tools from central Widgets +// if (!toolsMenuActions[CENTRAL_SEPARATOR]) +// { +// tempAction = ui.menuTools->addSeparator(); +// toolsMenuActions[CENTRAL_SEPARATOR] = tempAction; +// tempAction->setData(CENTRAL_SEPARATOR); +// } + + tempAction = ui.menuMain->addAction(title); tempAction->setCheckable(true); tempAction->setData(centralWidget); @@ -622,13 +647,17 @@ void MainWindow::addToCentralWidgetsMenu ( QWidget* widget, } // connect the action - connect(tempAction,SIGNAL(triggered()),this, slotName); + connect(tempAction,SIGNAL(triggered(bool)),this, slotName); } void MainWindow::showCentralWidget() { QAction* senderAction = qobject_cast(sender()); + + // Block sender action while manipulating state + senderAction->blockSignals(true); + int tool = senderAction->data().toInt(); QString chKey; @@ -636,7 +665,6 @@ void MainWindow::showCentralWidget() if (senderAction && dockWidgets[tool]) { - // uncheck all central widget actions QHashIterator i(toolsMenuActions); while (i.hasNext()) @@ -645,7 +673,11 @@ void MainWindow::showCentralWidget() //qDebug() << "shCW" << i.key() << "read"; if (i.value() && i.value()->data().toInt() > 255) { + // Block signals and uncheck action + // firing would be unneccesary + i.value()->blockSignals(true); i.value()->setChecked(false); + i.value()->blockSignals(false); // update the settings chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.value()->data().toInt()), currentView); @@ -664,6 +696,9 @@ void MainWindow::showCentralWidget() chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(tool), currentView); settings.setValue(chKey,true); + // Unblock sender action + senderAction->blockSignals(false); + presentView(); } } @@ -723,39 +758,60 @@ void MainWindow::addToToolsMenu ( QWidget* widget, } else { - tempAction->setChecked(settings.value(chKey).toBool()); + tempAction->setChecked(settings.value(chKey, false).toBool()); widget->setVisible(settings.value(chKey, false).toBool()); } // connect the action - connect(tempAction,SIGNAL(triggered()),this, slotName); + connect(tempAction,SIGNAL(toggled(bool)),this, slotName); + + connect(qobject_cast (dockWidgets[tool]), + SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool))); -// connect(qobject_cast (dockWidgets[tool]), -// SIGNAL(visibilityChanged(bool)), this, SLOT(updateVisibilitySettings(bool))); + // connect(qobject_cast (dockWidgets[tool]), + // SIGNAL(visibilityChanged(bool)), this, SLOT(updateVisibilitySettings(bool))); connect(qobject_cast (dockWidgets[tool]), SIGNAL(dockLocationChanged(Qt::DockWidgetArea)), this, SLOT(updateLocationSettings(Qt::DockWidgetArea))); - } -void MainWindow::showToolWidget() +void MainWindow::showToolWidget(bool visible) { - QAction* temp = qobject_cast(sender()); - int tool = temp->data().toInt(); - - if (temp && dockWidgets[tool]) + if (!aboutToCloseFlag && !changingViewsFlag) { - if (temp->isChecked()) - { - addDockWidget(dockWidgetLocations[tool], qobject_cast (dockWidgets[tool])); - qobject_cast(dockWidgets[tool])->show(); - } - else + QAction* action = qobject_cast(sender()); + int tool = action->data().toInt(); + + QDockWidget* dockWidget = qobject_cast (dockWidgets[tool]); + + if (action && dockWidget) { - removeDockWidget(qobject_cast(dockWidgets[tool])); + if (visible) + { + addDockWidget(dockWidgetLocations[tool], dockWidget); + dockWidget->show(); + } + + if (!visible && dockWidget->isVisible()) + { + removeDockWidget(dockWidget); + } + + + QHashIterator i(dockWidgets); + while (i.hasNext()) + { + i.next(); + if ((static_cast (dockWidgets[i.key()])) == dockWidget) + { + QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.key()), currentView); + settings.setValue(chKey,visible); + qDebug() << "showToolWidget(): Set key" << chKey << "to" << visible; + break; + } + } } } - } @@ -767,6 +823,8 @@ void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view) tempVisible = settings.value(buildMenuKey(SUB_SECTION_CHECKED,widget,view), false).toBool(); + qDebug() << "showTheWidget(): Set key" << buildMenuKey(SUB_SECTION_CHECKED,widget,view) << "to" << tempVisible; + if (tempWidget) { toolsMenuActions[widget]->setChecked(tempVisible); @@ -785,12 +843,14 @@ void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view) // } // } - if ((tempWidget != NULL) && tempVisible) + if (tempWidget != NULL) { - addDockWidget(tempLocation, tempWidget); - tempWidget->show(); + if (tempVisible) + { + addDockWidget(tempLocation, tempWidget); + tempWidget->show(); + } } - } QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view) @@ -802,11 +862,11 @@ QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES t UASManager::instance()->getActiveUAS()->getAutopilotType(): -1; - return (QString::number(apType) + "/" + - QString::number(SECTION_MENU) + "/" + - QString::number(view) + "/" + - QString::number(tool) + "/" + - QString::number(section) + "/" ); + return (QString::number(apType) + "_" + + QString::number(SECTION_MENU) + "_" + + QString::number(view) + "_" + + QString::number(tool) + "_" + + QString::number(section) + "_" ); } void MainWindow::closeEvent(QCloseEvent *event) @@ -824,6 +884,29 @@ void MainWindow::closeEvent(QCloseEvent *event) QMainWindow::closeEvent(event); } +void MainWindow::showDockWidget (bool vis) +{ + if (!aboutToCloseFlag && !changingViewsFlag) + { + QDockWidget* temp = qobject_cast(sender()); + + if (temp) + { + QHashIterator i(dockWidgets); + while (i.hasNext()) + { + i.next(); + if ((static_cast (dockWidgets[i.key()])) == temp) + { + QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.key()), currentView); + settings.setValue(chKey,vis); + toolsMenuActions[i.key()]->setChecked(vis); + break; + } + } + } + } +} void MainWindow::updateVisibilitySettings (bool vis) { @@ -834,9 +917,11 @@ void MainWindow::updateVisibilitySettings (bool vis) if (temp) { QHashIterator i(dockWidgets); - while (i.hasNext()) { + while (i.hasNext()) + { i.next(); - if ((static_cast (dockWidgets[i.key()])) == temp) { + if ((static_cast (dockWidgets[i.key()])) == temp) + { QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.key()), currentView); settings.setValue(chKey,vis); toolsMenuActions[i.key()]->setChecked(vis); @@ -1163,6 +1248,7 @@ void MainWindow::connectCommonActions() 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.actionUnconnectedView, SIGNAL(triggered()), this, SLOT(loadUnconnectedView())); connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView())); connect(ui.actionReloadStyle, SIGNAL(triggered()), this, SLOT(reloadStylesheet())); @@ -1309,8 +1395,13 @@ void MainWindow::UASCreated(UASInterface* uas) if (uas != NULL) { - // The pilot view was not available on startup, enable it now + // Set default settings + setDefaultSettingsForAp(); + + // 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); QIcon icon; // Set matching icon @@ -1404,6 +1495,7 @@ void MainWindow::UASCreated(UASInterface* uas) // } // } // } + } break; default: @@ -1424,8 +1516,6 @@ void MainWindow::UASCreated(UASInterface* uas) connectPxActions(); } break; - - loadOperatorView(); } // Change the view only if this is the first UAS @@ -1439,19 +1529,31 @@ void MainWindow::UASCreated(UASInterface* uas) // Load last view if setting is present if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED")) { + clearView(); 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())) + switch (view) { - restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion()); + 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; } } else { - loadEngineerView(); + loadOperatorView(); } } @@ -1469,7 +1571,7 @@ void MainWindow::UASCreated(UASInterface* uas) void MainWindow::clearView() { // Save current state - if (UASManager::instance()->getActiveUAS()) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); + if (UASManager::instance()->getUASList().count() > 0) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); settings.setValue(getWindowGeometryKey(), saveGeometry()); QAction* temp; @@ -1482,12 +1584,12 @@ void MainWindow::clearView() if (temp) { - //qDebug() << "TOOL:" << chKey << "IS:" << temp->isChecked(); + qDebug() << "TOOL:" << chKey << "IS:" << temp->isChecked(); settings.setValue(chKey,temp->isChecked()); } else { - //qDebug() << "TOOL:" << chKey << "IS DEFAULT AND UNCHECKED"; + qDebug() << "TOOL:" << chKey << "IS DEFAULT AND UNCHECKED"; settings.setValue(chKey,false); } } @@ -1504,11 +1606,8 @@ void MainWindow::clearView() 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? + removeDockWidget(dockWidget); + //dockWidget->setVisible(false); } } changingViewsFlag = false; @@ -1518,11 +1617,10 @@ void MainWindow::loadEngineerView() { if (currentView != VIEW_ENGINEER) { - clearView(); - - currentView = VIEW_ENGINEER; - - presentView(); + clearView(); + currentView = VIEW_ENGINEER; + ui.actionEngineersView->setChecked(true); + presentView(); } } @@ -1530,11 +1628,21 @@ void MainWindow::loadOperatorView() { if (currentView != VIEW_OPERATOR) { - clearView(); - - currentView = VIEW_OPERATOR; + clearView(); + currentView = VIEW_OPERATOR; + ui.actionOperatorsView->setChecked(true); + presentView(); + } +} - presentView(); +void MainWindow::loadUnconnectedView() +{ + if (currentView != VIEW_UNCONNECTED) + { + clearView(); + currentView = VIEW_UNCONNECTED; + ui.actionUnconnectedView->setChecked(true); + presentView(); } } @@ -1542,11 +1650,10 @@ void MainWindow::loadPilotView() { if (currentView != VIEW_PILOT) { - clearView(); - - currentView = VIEW_PILOT; - - presentView(); + clearView(); + currentView = VIEW_PILOT; + ui.actionPilotsView->setChecked(true); + presentView(); } } @@ -1554,11 +1661,10 @@ void MainWindow::loadMAVLinkView() { if (currentView != VIEW_MAVLINK) { - clearView(); - - currentView = VIEW_MAVLINK; - - presentView(); + clearView(); + currentView = VIEW_MAVLINK; + ui.actionMavlinkView->setChecked(true); + presentView(); } } @@ -1589,7 +1695,6 @@ void MainWindow::presentView() showTheCentralWidget(CENTRAL_DATA_PLOT, currentView); - // Show docked widgets based on current view and autopilot type // UAS CONTROL @@ -1664,8 +1769,28 @@ void MainWindow::presentView() // MAVLINK LOG PLAYER showTheWidget(MENU_MAVLINK_LOG_PLAYER, currentView); + // VIDEO 1 + showTheWidget(MENU_VIDEO_STREAM_1, currentView); + + // VIDEO 2 + showTheWidget(MENU_VIDEO_STREAM_2, currentView); + this->show(); + // Restore window state +// if (UASManager::instance()->getUASList().count() > 0) +// { +// // Restore the widget positions and size +// if (settings.contains(getWindowStateKey())) +// { +// restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion()); +// } + + if (settings.contains(getWindowGeometryKey())) + { + restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray()); + } +// } } void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view) @@ -1673,15 +1798,17 @@ void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SE 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; + tempVisible = settings.value(buildMenuKey(SUB_SECTION_CHECKED,centralWidget,view), false).toBool(); + qDebug() << buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view) << tempVisible; if (toolsMenuActions[centralWidget]) { + qDebug() << "SETTING TO:" << tempVisible; toolsMenuActions[centralWidget]->setChecked(tempVisible); } if (centerStack && tempWidget && tempVisible) { + qDebug() << "ACTIVATING MAIN WIDGET"; centerStack->setCurrentWidget(tempWidget); } } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index cb78a0738234993e82c9a042ab7cc67d59bdb3c9..25504031af09bbb1e7c99870d1d1963c9bf8e4f3 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -112,6 +112,8 @@ public slots: void stopVideoCapture(); void saveScreen(); + /** @brief Load default view when no MAV is connected */ + void loadUnconnectedView(); /** @brief Load view for pilot */ void loadPilotView(); /** @brief Load view for engineer */ @@ -166,7 +168,7 @@ public slots: * It shows the QDockedWidget based on the action sender * */ - void showToolWidget(); + void showToolWidget(bool visible); /** * @brief Shows a Widget from the center stack based on the action sender @@ -177,8 +179,10 @@ public slots: */ void showCentralWidget(); + /** @brief Change actively a QDockWidgets visibility by an action */ + void showDockWidget(bool vis); /** @brief Updates a QDockWidget's checked status based on its visibility */ - void updateVisibilitySettings (bool vis); + void updateVisibilitySettings(bool vis); /** @brief Updates a QDockWidget's location */ void updateLocationSettings (Qt::DockWidgetArea location); @@ -187,6 +191,9 @@ protected: MainWindow(QWidget *parent = 0); + /** @brief Set default window settings for the current autopilot type */ + void setDefaultSettingsForAp(); + // These defines are used to save the settings when selecting with // which widgets populate the views // FIXME: DO NOT PUT CUSTOM VALUES IN THIS ENUM since it is iterated over @@ -240,6 +247,7 @@ protected: VIEW_OPERATOR, VIEW_PILOT, VIEW_MAVLINK, + VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available } VIEW_SECTIONS; diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index 5808be0b0053bb85beee4a4b984c4d7dceda6936..85e8412f13c36da33604b7e93a6a358969609269 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -100,7 +100,7 @@ - Tools + Widgets @@ -121,11 +121,18 @@ + + + + + Main + + @@ -296,6 +303,9 @@ Operator + + Meta+O + @@ -308,6 +318,9 @@ Engineer + + Meta+E + @@ -320,6 +333,9 @@ Mavlink + + Meta+M + @@ -341,6 +357,9 @@ Pilot + + Meta+P + @@ -379,6 +398,21 @@ QGroundControl global settings + + + true + + + + :/images/devices/network-wireless.svg:/images/devices/network-wireless.svg + + + Unconnected + + + Meta+U + + diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index 27dc8acf94cfbfe6a0939e6b6f3d5f1b24e9d0b5..0bfb64ca4beb80e5c669155058c012a79d744543 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -308,7 +308,7 @@ Pixhawk3DWidget::insertWaypoint(void) if (wp) { wp->setFrame(frame); - uas->getWaypointManager().addWaypoint(wp); + uas->getWaypointManager()->addWaypoint(wp); } } } @@ -325,7 +325,7 @@ Pixhawk3DWidget::setWaypoint(void) if (uas) { const QVector waypoints = - uas->getWaypointManager().getWaypointList(); + uas->getWaypointManager()->getWaypointList(); Waypoint* waypoint = waypoints.at(selectedWpIndex); if (frame == MAV_FRAME_GLOBAL) @@ -366,7 +366,7 @@ Pixhawk3DWidget::deleteWaypoint(void) { if (uas) { - uas->getWaypointManager().removeWaypoint(selectedWpIndex); + uas->getWaypointManager()->removeWaypoint(selectedWpIndex); } } @@ -377,7 +377,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) { bool ok; const QVector waypoints = - uas->getWaypointManager().getWaypointList(); + uas->getWaypointManager()->getWaypointList(); Waypoint* waypoint = waypoints.at(selectedWpIndex); double altitude = waypoint->getZ(); @@ -409,10 +409,10 @@ Pixhawk3DWidget::clearAllWaypoints(void) if (uas) { const QVector waypoints = - uas->getWaypointManager().getWaypointList(); + uas->getWaypointManager()->getWaypointList(); for (int i = waypoints.size() - 1; i >= 0; --i) { - uas->getWaypointManager().removeWaypoint(i); + uas->getWaypointManager()->removeWaypoint(i); } } } diff --git a/src/ui/map3D/WaypointGroupNode.cc b/src/ui/map3D/WaypointGroupNode.cc index 26ba1612905ad043d683df3e87105158ac21bb92..deb08f643c229d1d8312c649a10c78effa37b2c0 100644 --- a/src/ui/map3D/WaypointGroupNode.cc +++ b/src/ui/map3D/WaypointGroupNode.cc @@ -78,7 +78,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas) removeChild(0, getNumChildren()); } - const QVector& list = uas->getWaypointManager().getWaypointList(); + const QVector& list = uas->getWaypointManager()->getWaypointList(); for (int i = 0; i < list.size(); i++) {