Newer
Older
Mariano Lizarraga
committed
// 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);
// 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();
}
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()),
hsiDockWidget);
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
Mariano Lizarraga
committed
void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view){
Mariano Lizarraga
committed
bool tempVisible;
QWidget* tempWidget = dockWidgets[centralWidget];
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();
}
}
// 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();
}
this->show();
//loadOperatorView();
Mariano Lizarraga
committed
loadMAVLinkView();
Mariano Lizarraga
committed
Mariano Lizarraga
committed
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
1378
1379
1380
1381
1382
1383
1384
1385
1386
1387
1388
1389
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
1400
1401
1402
1403
1404
1405
1406
1407
1408
1409
1410
1411
1412
1413
1414
1415
1416
1417
1418
1419
1420
1421
1422
1423
1424
1425
1426
1427
1428
1429
1430
1431
1432
1433
1434
1435
1436
1437
1438
1439
1440
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
1454
1455
1456
1457
1458
1459
1460
1461
1462
1463
1464
1465
1466
1467
1468
1469
1470
1471
1472
1473
1474
1475
1476
1477
1478
1479
1480
1481
1482
1483
1484
1485
1486
1487
1488
1489
1490
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
1513
1514
1515
1516
1517
1518
1519
1520
1521
1522
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
1535
1536
1537
1538
1539
1540
1541
1542
1543
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
this->show();
}
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();
}
}
this->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
this->show();
}
Mariano Lizarraga
committed
1544
1545
1546
1547
1548
1549
1550
1551
1552
1553
1554
1555
1556
1557
1558
1559
1560
1561
1562
1563
1564
1565
1566
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
1595
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
/*
==================================
========== 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())
}
*/