Newer
Older
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();
}
}
{
joystickWidget = new JoystickWidget(joystick, this);
}
{
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();
// TODO Implement the link removal!
}
void MainWindow::addLink(LinkInterface *link)
{
LinkManager::instance()->addProtocol(link, mavlink);
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)));
connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
}
}
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
if (uas != NULL)
{
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)
{
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
if (infoDockWidget)
{
UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
if (infoWidget)
{
infoWidget->addUAS(uas);
}
// UAS List
if (listDockWidget)
{
UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
if (listWidget)
{
listWidget->addUAS(uas);
}
// Camera view
//camera->addUAS(uas);
// Revalidate UI
// TODO Stylesheet reloading should in theory not be necessary
reloadStylesheet();
Mariano Lizarraga
committed
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
switch (uas->getAutopilotType()){
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();
// FIXME: This type checking might be redundant
// Check which type this UAS is of
// PxQuadMAV* mav = dynamic_cast<PxQuadMAV*>(uas);
// if (mav) loadPixhawkEngineerView();
} break;
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
Mariano Lizarraga
committed
if (slugsDataWidget) {
SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
if (dataWidget) {
Mariano Lizarraga
committed
(dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget()))->addUAS(uas);
Mariano Lizarraga
committed
}
}
Mariano Lizarraga
committed
} break;
loadEngineerView();
Mariano Lizarraga
committed
/**
* Clears the current view completely
*/
Mariano Lizarraga
committed
// Halt HUD central widget
if (hudWidget) hudWidget->stop();
Mariano Lizarraga
committed
// Disable linechart
if (linechartWidget) linechartWidget->setActive(false);
Mariano Lizarraga
committed
// Halt HDDs
if (headDown1DockWidget)
{
HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown1DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
Mariano Lizarraga
committed
{
HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown2DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
Mariano Lizarraga
committed
// Halt HSI
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi) hsi->stop();
}
Mariano Lizarraga
committed
// Halt HUD if in docked widget mode
if (headUpDockWidget)
{
HUD* hud = dynamic_cast<HUD*>( headUpDockWidget->widget() );
if (hud) hud->stop();
}
// Remove all dock widgets from main window
QObjectList childList( this->children() );
QObjectList::iterator i;
QDockWidget* dockWidget;
for (i = childList.begin(); i != childList.end(); ++i)
dockWidget = dynamic_cast<QDockWidget*>(*i);
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?
Mariano Lizarraga
committed
void MainWindow::loadEngineerView()
Mariano Lizarraga
committed
clearView();
Mariano Lizarraga
committed
currentView = VIEW_ENGINEER;
Mariano Lizarraga
committed
presentView();
Mariano Lizarraga
committed
void MainWindow::loadOperatorView()
Mariano Lizarraga
committed
clearView();
currentView = VIEW_OPERATOR;
Mariano Lizarraga
committed
presentView();
Mariano Lizarraga
committed
void MainWindow::loadPilotView()
Mariano Lizarraga
committed
currentView = VIEW_PILOT;
presentView();
Mariano Lizarraga
committed
void MainWindow::loadMAVLinkView()
{
clearView();
Mariano Lizarraga
committed
currentView = VIEW_MAVLINK;
presentView();
//=======
// // Slugs Data View
// if (slugsHilSimWidget)
// {
// addDockWidget(Qt::LeftDockWidgetArea, slugsHilSimWidget);
// slugsHilSimWidget->show();
// }
//>>>>>>> master
}
Mariano Lizarraga
committed
void MainWindow::presentView() {
Mariano Lizarraga
committed
#ifdef QGC_OSG_ENABLED
// 3D map
if (_3DWidget)
{
if (centerStack)
{
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(_3DWidget);
}
}
#endif
Mariano Lizarraga
committed
qDebug() << "LC";
showTheCentralWidget(CENTRAL_LINECHART, currentView);
Mariano Lizarraga
committed
if (linechartWidget){
qDebug () << buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_LINECHART,currentView) <<
settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_LINECHART,currentView)).toBool() ;
if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_LINECHART,currentView)).toBool()){
if (centerStack) {
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
} else {
linechartWidget->setActive(false);
}
}
Mariano Lizarraga
committed
// MAP
qDebug() << "MAP";
showTheCentralWidget(CENTRAL_MAP, currentView);
Mariano Lizarraga
committed
// PROTOCOL
qDebug() << "CP";
showTheCentralWidget(CENTRAL_PROTOCOL, currentView);
Mariano Lizarraga
committed
// HEAD UP DISPLAY
showTheCentralWidget(CENTRAL_HUD, currentView);
Mariano Lizarraga
committed
qDebug() << "HUD";
if (hudWidget){
qDebug() << buildMenuKey(SUB_SECTION_CHECKED,CENTRAL_HUD,currentView) <<
settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_HUD,currentView)).toBool();
if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_HUD,currentView)).toBool()){
if (centerStack) {
centerStack->setCurrentWidget(hudWidget);
hudWidget->start();
}
} else {
hudWidget->stop();
}
}
Mariano Lizarraga
committed
// Show docked widgets based on current view and autopilot type
Mariano Lizarraga
committed
// UAS CONTROL
showTheWidget(MENU_UAS_CONTROL, currentView);
Mariano Lizarraga
committed
// UAS LIST
showTheWidget(MENU_UAS_LIST, currentView);
Mariano Lizarraga
committed
// WAYPOINT LIST
showTheWidget(MENU_WAYPOINTS, currentView);
Mariano Lizarraga
committed
// UAS STATUS
showTheWidget(MENU_STATUS, currentView);
Mariano Lizarraga
committed
// 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);
Mariano Lizarraga
committed
if (headUpDockWidget)
{
HUD* tmpHud = dynamic_cast<HUD*>( headUpDockWidget->widget() );
if (tmpHud){
if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HUD,currentView)).toBool()){
tmpHud->start();
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HUD, currentView)).toInt()),
headUpDockWidget);
Mariano Lizarraga
committed
headUpDockWidget->show();
} else {
tmpHud->stop();
headUpDockWidget->hide();
}
}
}
Mariano Lizarraga
committed
// 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
Mariano Lizarraga
committed
showTheWidget(MENU_HSI, currentView);
Mariano Lizarraga
committed
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
Mariano Lizarraga
committed
if (hsi){
if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
Mariano Lizarraga
committed
hsi->start();
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
hsiDockWidget);
hsiDockWidget->show();
Mariano Lizarraga
committed
} else {
hsi->stop();
hsiDockWidget->hide();
}
Mariano Lizarraga
committed
}
}
// HEAD DOWN 1
Mariano Lizarraga
committed
showTheWidget(MENU_HDD_1, currentView);
Mariano Lizarraga
committed
if (headDown1DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
Mariano Lizarraga
committed
if (hdd) {
if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool()) {
Mariano Lizarraga
committed
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
headDown1DockWidget);
headDown1DockWidget->show();
hdd->start();
Mariano Lizarraga
committed
} else {
headDown1DockWidget->hide();;
hdd->stop();
}
Mariano Lizarraga
committed
}
}
// HEAD DOWN 2
Mariano Lizarraga
committed
showTheWidget(MENU_HDD_2, currentView);
Mariano Lizarraga
committed
if (headDown2DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
Mariano Lizarraga
committed
if (hdd){
if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool()){
Mariano Lizarraga
committed
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
headDown2DockWidget);
headDown2DockWidget->show();
hdd->start();
Mariano Lizarraga
committed
} else {
headDown2DockWidget->hide();
hdd->stop();
}
Mariano Lizarraga
committed
}
}
this->show();
Mariano Lizarraga
committed
pixhawk
committed
}
Mariano Lizarraga
committed
void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view){
Mariano Lizarraga
committed
bool tempVisible;
QWidget* tempWidget = dockWidgets[centralWidget];
//=======
// // ONBOARD PARAMETERS
// if (parametersDockWidget)
// {
// addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
// parametersDockWidget->show();
// }
//}
//>>>>>>> master
Mariano Lizarraga
committed
tempVisible = settings.value(buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view)).toBool();
Mariano Lizarraga
committed
qDebug() << buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view) << tempVisible;
Mariano Lizarraga
committed
if (toolsMenuActions[centralWidget]){
toolsMenuActions[centralWidget]->setChecked(tempVisible);
}
if (centerStack && tempWidget && tempVisible){
centerStack->setCurrentWidget(tempWidget);
}
}
Mariano Lizarraga
committed
/*
==========================================================
Potentially Deprecated
==========================================================
*/
void MainWindow::loadPixhawkEngineerView()
{
}
void MainWindow::loadAllView()
{
clearView();
if (headDown1DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
if (hdd)
{
addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
headDown1DockWidget->show();
hdd->start();
}
Mariano Lizarraga
committed
}
if (headDown2DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
if (hdd)
{
addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
headDown2DockWidget->show();
hdd->start();
}
}
//void MainWindow::loadOperatorView()
//{
// clearView();
// // MAP
// if (mapWidget)
// {
// QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
// if (centerStack)
// {
// centerStack->setCurrentWidget(mapWidget);
// }
// }
//>>>>>>> master
// UAS CONTROL
if (controlDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST
if (listDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS
if (infoDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE
if (debugConsoleDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
// OBJECT DETECTION
if (detectionDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
detectionDockWidget->show();
// LINE CHART
if (linechartWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
//loadOperatorView();
Mariano Lizarraga
committed
loadMAVLinkView();
Mariano Lizarraga
committed
Mariano Lizarraga
committed
1596
1597
1598
1599
1600
1601
1602
1603
1604
1605
1606
1607
1608
1609
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
1681
1682
1683
1684
1685
1686
1687
1688
1689
1690
1691
1692
1693
1694
1695
1696
1697
1698
1699
1700
1701
1702
1703
1704
1705
1706
1707
1708
1709
1710
1711
1712
1713
1714
1715
1716
1717
1718
1719
1720
1721
1722
1723
1724
1725
1726
1727
1728
1729
1730
1731
1732
1733
1734
1735
1736
1737
1738
1739
1740
1741
1742
1743
1744
1745
1746
1747
1748
1749
1750
1751
1752
1753
1754
1755
1756
1757
1758
1759
1760
1761
1762
1763
1764
1765
1766
1767
1768
1769
1770
1771
1772
1773
1774
1775
1776
void MainWindow::loadDataView()
{
clearView();
// DATAPLOT
if (dataplotWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
centerStack->setCurrentWidget(dataplotWidget);
}
}
void MainWindow::loadDataView(QString fileName)
{
clearView();
// DATAPLOT
if (dataplotWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(dataplotWidget);
dataplotWidget->loadFile(fileName);
}
}
}
void MainWindow::load3DMapView()
{
#ifdef QGC_OSGEARTH_ENABLED
clearView();
// 3D map
if (_3DMapWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(_3DMapWidget);
}
}
// 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();
}
}
#endif
}
void MainWindow::loadGoogleEarthView()
{
#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
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();
}
}
#endif
}
void MainWindow::load3DView()
{
#ifdef QGC_OSG_ENABLED
clearView();
// 3D map
if (_3DWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(_3DWidget);
}
}
// 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();
}
}
#endif
}
Mariano Lizarraga
committed
/*
==================================
========== ATTIC =================
==================================
void MainWindow::buildWidgets()
Mariano Lizarraga
committed
1784
1785
1786
1787
1788
1789
1790
1791
1792
1793
1794
1795
1796
1797
1798
1799
1800
1801
1802
1803
1804
1805
1806
1807
1808
1809
1810
1811
1812
1813
1814
1815
1816
1817
1818
1819
1820
1821
1822
1823
1824
1825
{
//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) );
Mariano Lizarraga
committed
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) );
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
Mariano Lizarraga
committed
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
Mariano Lizarraga
committed
1846
1847
1848
1849
1850
1851
1852
1853
1854
1855
1856
1857
1858
1859
1860
1861
1862
1863
1864
1865
1866
1867
1868
1869
1870
1871
1872
1873
1874
1875
1876
1877
1878
1879
1880
1881
1882
1883
1884
1885
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));
if (protocolWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(protocolWidget);
}
}
Mariano Lizarraga
committed
1896
1897
1898
1899
1900
1901
1902
1903
1904
1905
1906
1907
1908
1909
1910
1911
1912
1913
1914
1915
1916
1917
1918
1919
1920
1921
1922
1923
1924
1925
1926
1927
1928
1929
1930
1931
1932
1933
1934
1935
1936
1937
1938
1939
1940
1941
1942
1943
1944
1945
1946
}
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::arrangeCenterStack()
Mariano Lizarraga
committed
{
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);
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
Mariano Lizarraga
committed
}
void MainWindow::connectActions()
{
Mariano Lizarraga
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*)));
// 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()));