Newer
Older
}
}
void MainWindow::showRoadMap()
{
if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/dev/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();
}
}
if (!joystickWidget) {
if (!joystick->isRunning()) {
joystick->start();
}
joystickWidget = new JoystickWidget(joystick);
}
joystickWidget->show();
void MainWindow::showSettings()
{
QGCSettingsWidget* settings = new QGCSettingsWidget(this);
settings->show();
}
{
SerialLink* link = new SerialLink();
// TODO This should be only done in the dialog itself
LinkManager::instance()->add(link);
// 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))
{
act->trigger();
break;
}
}
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();
bool found = false;
foreach (QAction* act, actions) {
if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link)) {
found = true;
}
}
UDPLink* udp = dynamic_cast<UDPLink*>(link);
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());
}
}
}
// The pilot, operator and engineer views were not available on startup, enable them now
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);
QIcon icon;
// Set matching icon
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
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
DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
}
// Health / System status indicator
UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
// UAS List
UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
// Line chart
if (!linechartWidget)
// Center widgets
linechartWidget = new Linecharts(this);
//linechartWidget FIXME
addCentralWidget(linechartWidget, tr("Realtime Plot"));
// Load default custom widgets for this autopilot type
loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName());
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)
{
if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED"))
{
int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt();
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
{
Mariano Lizarraga
committed
if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
// Restore the mainwindow size
if (settings.contains(getWindowGeometryKey()))
{
restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray());
}
* Stores the current view state
void MainWindow::storeViewState()
// 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
int index = settings.value(getWindowStateKey()+"CENTER_WIDGET", -1).toInt();
// 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);
}
if (index != -1)
{
centerStack->setCurrentIndex(index);
}
else
{
// Load defaults
switch (currentView)
{
case VIEW_ENGINEER:
centerStack->setCurrentWidget(linechartWidget);
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();
break;
case VIEW_PILOT:
centerStack->setCurrentWidget(hudWidget);
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();
break;
case VIEW_MAVLINK:
centerStack->setCurrentWidget(protocolWidget);
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();
break;
case VIEW_OPERATOR:
case VIEW_UNCONNECTED:
case VIEW_FULL:
default:
centerStack->setCurrentWidget(mapWidget);
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();
// Restore the widget positions and size
if (settings.contains(getWindowStateKey()))
{
restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion());
Mariano Lizarraga
committed
void MainWindow::loadEngineerView()
if (currentView != VIEW_ENGINEER) {
storeViewState();
currentView = VIEW_ENGINEER;
ui.actionEngineersView->setChecked(true);
loadViewState();
Mariano Lizarraga
committed
void MainWindow::loadOperatorView()
if (currentView != VIEW_OPERATOR) {
storeViewState();
currentView = VIEW_OPERATOR;
ui.actionOperatorsView->setChecked(true);
loadViewState();
void MainWindow::loadUnconnectedView()
{
if (currentView != VIEW_UNCONNECTED)
{
storeViewState();
currentView = VIEW_UNCONNECTED;
ui.actionUnconnectedView->setChecked(true);
loadViewState();
Mariano Lizarraga
committed
void MainWindow::loadPilotView()
if (currentView != VIEW_PILOT)
{
storeViewState();
currentView = VIEW_PILOT;
ui.actionPilotsView->setChecked(true);
loadViewState();
Mariano Lizarraga
committed
void MainWindow::loadMAVLinkView()
if (currentView != VIEW_MAVLINK)
{
storeViewState();
currentView = VIEW_MAVLINK;
ui.actionMavlinkView->setChecked(true);
loadViewState();
Mariano Lizarraga
committed
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);
Mariano Lizarraga
committed
}
QList<QAction*> MainWindow::listLinkMenuActions(void)
{