MainWindow.cc 55.7 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5
======================================================================*/

/**
 * @file
6
 *   @brief Implementation of class MainWindow
7
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26
 */

#include <QSettings>
#include <QDockWidget>
#include <QNetworkInterface>
#include <QMessageBox>
#include <QDebug>
#include <QTimer>
#include <QHostInfo>

#include "MG.h"
#include "MAVLinkSimulationLink.h"
#include "SerialLink.h"
#include "UDPLink.h"
#include "MAVLinkProtocol.h"
#include "CommConfigurationWindow.h"
#include "WaypointList.h"
#include "MainWindow.h"
#include "JoystickWidget.h"
pixhawk's avatar
pixhawk committed
27
#include "GAudioOutput.h"
28

29
#ifdef QGC_OSG_ENABLED
30
#include "Q3DWidgetFactory.h"
31
#endif
pixhawk's avatar
pixhawk committed
32

lm's avatar
lm committed
33 34 35 36
// FIXME Move
#include "PxQuadMAV.h"
#include "SlugsMAV.h"

pixhawk's avatar
pixhawk committed
37 38 39 40 41 42 43 44 45 46

#include "LogCompressor.h"

/**
* Create new mainwindow. The constructor instantiates all parts of the user
* interface. It does NOT show the mainwindow. To display it, call the show()
* method.
*
* @see QMainWindow::show()
**/
47
MainWindow::MainWindow(QWidget *parent):
pixhawk's avatar
pixhawk committed
48
        QMainWindow(parent),
49
        toolsMenuActions(),
50
        currentView(VIEW_MAVLINK),
pixhawk's avatar
pixhawk committed
51
        settings()
pixhawk's avatar
pixhawk committed
52
{
53 54 55
    this->hide();
    this->setVisible(false);

pixhawk's avatar
pixhawk committed
56 57 58
    // Setup user interface
    ui.setupUi(this);

59
    buildCommonWidgets();
60

61
    connectCommonWidgets();
62

63
    arrangeCommonCenterStack();
64 65

    configureWindowName();
pixhawk's avatar
pixhawk committed
66 67

    // Add status bar
68
    //setStatusBar(createStatusBar());
pixhawk's avatar
pixhawk committed
69 70 71 72

    // Set the application style (not the same as a style sheet)
    // Set the style to Plastique
    qApp->setStyle("plastique");
73

pixhawk's avatar
pixhawk committed
74 75 76
    // Set style sheet as last step
    reloadStylesheet();

77
    // Create actions
78
    connectCommonActions();
79

80 81
    // Load mavlink view as default widget set
    loadMAVLinkView();
82 83 84

    // Adjust the size
    adjustSize();
pixhawk's avatar
pixhawk committed
85 86
}

pixhawk's avatar
pixhawk committed
87
MainWindow::~MainWindow()
pixhawk's avatar
pixhawk committed
88 89 90 91 92
{
    delete statusBar;
    statusBar = NULL;
}

93 94 95 96 97 98 99 100
void MainWindow::buildCommonWidgets()
{
    //TODO:  move protocol outside UI
    mavlink     = new MAVLinkProtocol();

    // Dock widgets
    controlDockWidget = new QDockWidget(tr("Control"), this);
    controlDockWidget->setWidget( new UASControlWidget(this) );
101
    addToToolsMenu (controlDockWidget, tr("UAS Control"), SLOT(showToolWidget()), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea);
102 103 104

    listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
    listDockWidget->setWidget( new UASListWidget(this) );
105
    addToToolsMenu (listDockWidget, tr("UAS List"), SLOT(showToolWidget()), MENU_UAS_LIST, Qt::RightDockWidgetArea);
106 107 108

    waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
    waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
109
    addToToolsMenu (waypointsDockWidget, tr("Waypoints List"), SLOT(showToolWidget()), MENU_WAYPOINTS, Qt::BottomDockWidgetArea);
110 111 112

    infoDockWidget = new QDockWidget(tr("Status Details"), this);
    infoDockWidget->setWidget( new UASInfoWidget(this) );
113 114
    addToToolsMenu (infoDockWidget, tr("Status Details"), SLOT(showToolWidget()), MENU_STATUS, Qt::RightDockWidgetArea);

115 116 117

    debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
    debugConsoleDockWidget->setWidget( new DebugConsole(this) );
118
    addToToolsMenu (debugConsoleDockWidget, tr("Communication Console"), SLOT(showToolWidget()), MENU_DEBUG_CONSOLE, Qt::BottomDockWidgetArea);
119

120 121
    // Center widgets
    mapWidget         = new MapWidget(this);
122 123
    addToCentralWidgetsMenu (mapWidget, "Maps", SLOT(showCentralWidget()),CENTRAL_MAP);

124
    protocolWidget    = new XMLCommProtocolWidget(this);
125 126
    addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL);

127

128
}
129

130
void MainWindow::buildPxWidgets()
131
{
pixhawk's avatar
pixhawk committed
132 133 134 135 136 137 138 139
    //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");
140

pixhawk's avatar
pixhawk committed
141 142 143 144
    //FIXME: memory of acceptList2 will never be freed again
    QStringList* acceptList2 = new QStringList();
    acceptList2->append("Battery");
    acceptList2->append("Pressure");
145

pixhawk's avatar
pixhawk committed
146 147
    // Center widgets
    linechartWidget   = new Linecharts(this);
148 149 150
    addToCentralWidgetsMenu(linechartWidget, "Line Plots", SLOT(showCentralWidget()), CENTRAL_LINECHART);


151
    hudWidget         = new HUD(320, 240, this);
152 153
    addToCentralWidgetsMenu(hudWidget, "HUD", SLOT(showCentralWidget()), CENTRAL_HUD);

pixhawk's avatar
pixhawk committed
154
    dataplotWidget    = new QGCDataPlot2D(this);
155
    addToCentralWidgetsMenu(dataplotWidget, "Data Plots", SLOT(showCentralWidget()), CENTRAL_DATA_PLOT);
156

157
#ifdef QGC_OSG_ENABLED
158
    _3DWidget         = Q3DWidgetFactory::get("PIXHAWK");
159 160
    addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);

161
#endif
162

163 164
#ifdef QGC_OSGEARTH_ENABLED
    _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
165 166
    addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);

167
#endif
168
#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
pixhawk's avatar
pixhawk committed
169
    gEarthWidget = new QGCGoogleEarthView(this);
170 171
    addToCentralWidgetsMenu(gEarthWidget, "Google Earth", SLOT(showCentralWidget()), CENTRAL_GOOGLE_EARTH);

172
#endif
173

pixhawk's avatar
pixhawk committed
174 175 176
    // Dock widgets
    detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
    detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
177 178
    addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget()), MENU_DETECTION, Qt::RightDockWidgetArea);

179

pixhawk's avatar
pixhawk committed
180 181
    parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
    parametersDockWidget->setWidget( new ParameterInterface(this) );
182
    addToToolsMenu (parametersDockWidget, tr("Onboard Parameters"), SLOT(showToolWidget()), MENU_PARAMETERS, Qt::RightDockWidgetArea);
183

pixhawk's avatar
pixhawk committed
184 185
    watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
    watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
186 187
    addToToolsMenu (watchdogControlDockWidget, tr("Process Control"), SLOT(showToolWidget()), MENU_WATCHDOG, Qt::BottomDockWidgetArea);

188

pixhawk's avatar
pixhawk committed
189 190
    hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
    hsiDockWidget->setWidget( new HSIDisplay(this) );
191
    addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget()), MENU_HSI, Qt::BottomDockWidgetArea);
192

pixhawk's avatar
pixhawk committed
193 194
    headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
    headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
195
    addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
196

pixhawk's avatar
pixhawk committed
197 198
    headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
    headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
199
    addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea);
200

pixhawk's avatar
pixhawk committed
201 202
    rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
    rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
203
    addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
204

205
    headUpDockWidget = new QDockWidget(tr("HUD"), this);
206
    headUpDockWidget->setWidget( new HUD(320, 240, this));
207
    addToToolsMenu (headUpDockWidget, tr("Control Indicator"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
208

pixhawk's avatar
pixhawk committed
209 210 211
    // Dialogue widgets
    //FIXME: free memory in destructor
    joystick    = new JoystickInput();
212

213 214 215 216 217 218 219 220
}

void MainWindow::buildSlugsWidgets()
{
    // Center widgets
    linechartWidget   = new Linecharts(this);

    // Dock widgets
221 222 223 224 225
    headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
    headUpDockWidget->setWidget( new HUD(320, 240, this));
    addToToolsMenu (headUpDockWidget, tr("HUD"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);


226 227
    rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
    rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
228
    addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
229 230 231


    // Dialog widgets
232 233
    slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
    slugsDataWidget->setWidget( new SlugsDataSensorView(this));
234 235
    addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);

236

237 238
    slugsPIDControlWidget = new QDockWidget(tr("PID Control"), this);
    slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
239
    addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
240

241 242
    slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
    slugsHilSimWidget->setWidget( new SlugsHilSim(this));
243
    addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
244

245 246
    slugsCamControlWidget = new QDockWidget(tr("Video Camera Control"), this);
    slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
247
    addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
248

249
}
250 251 252 253 254 255 256 257


void MainWindow::addToCentralWidgetsMenu ( QWidget* widget,
                                           const QString title,
                                           const char * slotName,
                                           TOOLS_WIDGET_NAMES centralWidget){
  QAction* tempAction;

258

259 260 261 262
  // Add the separator that will separate tools from central Widgets
  if (!toolsMenuActions[CENTRAL_SEPARATOR]){
    tempAction = ui.menuTools->addSeparator();
    toolsMenuActions[CENTRAL_SEPARATOR] = tempAction;
263
    tempAction->setData(CENTRAL_SEPARATOR);
264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280
  }

  tempAction = ui.menuTools->addAction(title);

  tempAction->setCheckable(true);
  tempAction->setData(centralWidget);

  // populate the Hashes
  toolsMenuActions[centralWidget] = tempAction;
  dockWidgets[centralWidget] = widget;

  QString chKey = buildMenuKey(SUB_SECTION_CHECKED, centralWidget, currentView);

  if (!settings.contains(chKey)){
    settings.setValue(chKey,false);
    tempAction->setChecked(false);
  }
281 282 283
//  else {
//    tempAction->setChecked(settings.value(chKey).toBool());
//  }
284 285 286 287 288 289 290 291 292 293 294 295

  // connect the action
  connect(tempAction,SIGNAL(triggered()),this, slotName);

}


void MainWindow::showCentralWidget(){
  QAction* senderAction = qobject_cast<QAction *>(sender());
  int tool = senderAction->data().toInt();
  QString chKey;

296 297
  // check the current action

298 299 300 301 302
  if (senderAction && dockWidgets[tool]){

    // uncheck all central widget actions
    QHashIterator<int, QAction*> i(toolsMenuActions);
     while (i.hasNext()) {
303 304 305
       i.next();
       qDebug() << "shCW" << i.key() << "read";
       if (i.value() && i.value()->data().toInt() > 255){
306 307 308 309 310 311 312 313 314
           i.value()->setChecked(false);

           // update the settings
           chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(i.value()->data().toInt()), currentView);
           settings.setValue(chKey,false);
         }
     }

    // check the current action
315
     qDebug() << senderAction->text();
316 317 318 319 320 321 322 323
    senderAction->setChecked(true);

    // update the central widget
    centerStack->setCurrentWidget(dockWidgets[tool]);

    // store the selected central widget
    chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(tool), currentView);
    settings.setValue(chKey,true);
324 325

   presentView();
326 327
  }
}
328 329 330 331 332 333 334 335

void MainWindow::addToToolsMenu ( QWidget* widget,
                                 const QString title,
                                 const char * slotName,
                                 TOOLS_WIDGET_NAMES tool,
                                 Qt::DockWidgetArea location){
  QAction* tempAction;
  QString posKey, chKey;
336

337

338 339 340 341 342 343 344 345
  if (toolsMenuActions[CENTRAL_SEPARATOR]){
    tempAction = new QAction(title, this);
    ui.menuTools->insertAction(toolsMenuActions[CENTRAL_SEPARATOR],
                               tempAction);
  } else {
    tempAction = ui.menuTools->addAction(title);
  }

346 347 348 349 350 351
  tempAction->setCheckable(true);
  tempAction->setData(tool);

  // populate the Hashes
  toolsMenuActions[tool] = tempAction;
  dockWidgets[tool] = widget;
352
  qDebug() << widget;
353

354
  posKey = buildMenuKey (SUB_SECTION_LOCATION,tool, currentView);
355 356 357 358 359 360 361 362

  if (!settings.contains(posKey)){
    settings.setValue(posKey,location);
    dockWidgetLocations[tool] = location;
  } else {
    dockWidgetLocations[tool] = static_cast <Qt::DockWidgetArea> (settings.value(posKey).toInt());
  }

363
  chKey = buildMenuKey(SUB_SECTION_CHECKED,tool, currentView);
364 365 366 367 368 369 370 371 372 373 374

  if (!settings.contains(chKey)){
    settings.setValue(chKey,false);
    tempAction->setChecked(false);
  } else {
    tempAction->setChecked(settings.value(chKey).toBool());
  }

  // connect the action
  connect(tempAction,SIGNAL(triggered()),this, slotName);

375
  connect(qobject_cast <QDockWidget *>(dockWidgets[tool]),
376 377
          SIGNAL(visibilityChanged(bool)), this, SLOT(updateVisibilitySettings(bool)));

378
  connect(qobject_cast <QDockWidget *>(dockWidgets[tool]),
379 380 381 382
          SIGNAL(dockLocationChanged(Qt::DockWidgetArea)), this, SLOT(updateLocationSettings(Qt::DockWidgetArea)));

}

383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423
void MainWindow::showToolWidget(){
  QAction* temp = qobject_cast<QAction *>(sender());
  int tool = temp->data().toInt();


  if (temp && dockWidgets[tool]){
    if (temp->isChecked()){
      addDockWidget(dockWidgetLocations[tool], qobject_cast<QDockWidget *> (dockWidgets[tool]));
      qobject_cast<QDockWidget *>(dockWidgets[tool])->show();
    } else {
      removeDockWidget(qobject_cast<QDockWidget *>(dockWidgets[tool]));
    }
    QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(tool), currentView);
    settings.setValue(chKey,temp->isChecked());
  }
}


void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view){
  bool tempVisible;
  Qt::DockWidgetArea tempLocation;
  QDockWidget* tempWidget = static_cast <QDockWidget *>(dockWidgets[widget]);

  tempVisible =  settings.value(buildMenuKey (SUB_SECTION_CHECKED,widget,view)).toBool();

  if (tempWidget){
    toolsMenuActions[widget]->setChecked(tempVisible);
  }


  //qDebug() <<  buildMenuKey (SUB_SECTION_CHECKED,widget,view) << tempVisible;

  tempLocation = static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,widget, view)).toInt());

  if (tempWidget && tempVisible){
    addDockWidget(tempLocation, tempWidget);
    tempWidget->show();
  }

}

424 425 426 427 428 429 430 431 432 433 434
QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view){
  // Key is built as follows: autopilot_type/section_menu/view/tool/section
  int apType;

  apType = (UASManager::instance() && UASManager::instance()->silentGetActiveUAS())?
           UASManager::instance()->getActiveUAS()->getAutopilotType():
           -1;

  return (QString::number(apType) + "/" +
          QString::number(SECTION_MENU) + "/" +
          QString::number(view) + "/" +
435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471
          QString::number(tool) + "/" +
          QString::number(section) + "/" );
}

void MainWindow::updateVisibilitySettings (bool vis){
  Q_UNUSED(vis);

  // This is commented since when the application closes
  // sets the visibility to false.

  // TODO: A workaround is needed. The QApplication::aboutToQuit
  //       did not work

  /*
  QDockWidget* temp = qobject_cast<QDockWidget *>(sender());

  QHashIterator<int, QWidget*> i(dockWidgets);
  while (i.hasNext()) {
      i.next();
      if ((static_cast <QDockWidget *>(dockWidgets[i.key()])) == temp){
        QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(i.key()));
        qDebug() << "Key in visibility changed" << chKey;
        settings.setValue(chKey,vis);
        toolsMenuActions[i.key()]->setChecked(vis);
        break;
      }
  }
*/
}

void MainWindow::updateLocationSettings (Qt::DockWidgetArea location){
  QDockWidget* temp = qobject_cast<QDockWidget *>(sender());

  QHashIterator<int, QWidget*> i(dockWidgets);
  while (i.hasNext()) {
      i.next();
      if ((static_cast <QDockWidget *>(dockWidgets[i.key()])) == temp){
472
        QString posKey = buildMenuKey (SUB_SECTION_LOCATION,static_cast<TOOLS_WIDGET_NAMES>(i.key()), currentView);
473 474 475 476 477 478
        settings.setValue(posKey,location);
        break;
      }
  }
}

479 480 481
/**
 * Connect the signals and slots of the common window widgets
 */
482
void MainWindow::connectCommonWidgets()
483
{
pixhawk's avatar
pixhawk committed
484 485 486 487 488
    if (infoDockWidget && infoDockWidget->widget())
    {
        connect(mavlink, SIGNAL(receiveLossChanged(int, float)),
                infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
    }
489

pixhawk's avatar
pixhawk committed
490 491 492 493 494 495
    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)));
496 497 498

        // 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)));
499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526
    }

}

void MainWindow::connectPxWidgets()
{
    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)));
    }

}

void MainWindow::connectSlugsWidgets()
{
    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)));
pixhawk's avatar
pixhawk committed
527
    }
528

529 530 531 532 533 534 535 536
    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*)));
537 538
    }

539

540 541
}

542
void MainWindow::arrangeCommonCenterStack()
543
{
544
    centerStack = new QStackedWidget(this);
545

pixhawk's avatar
pixhawk committed
546
    if (!centerStack) return;
547

pixhawk's avatar
pixhawk committed
548
    if (mapWidget) centerStack->addWidget(mapWidget);
549 550 551 552 553 554 555 556 557 558 559 560 561 562 563
    if (protocolWidget) centerStack->addWidget(protocolWidget);

    setCentralWidget(centerStack);
}

void MainWindow::arrangePxCenterStack()
{

  if (!centerStack) {
    qDebug() << "Center Stack not Created!";
    return;
  }

    if (linechartWidget) centerStack->addWidget(linechartWidget);

564
#ifdef QGC_OSG_ENABLED
565
    if (_3DWidget) centerStack->addWidget(_3DWidget);
566
#endif
567
#ifdef QGC_OSGEARTH_ENABLED
568
    if (_3DMapWidget) centerStack->addWidget(_3DMapWidget);
569 570
#endif
#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
pixhawk's avatar
pixhawk committed
571
    if (gEarthWidget) centerStack->addWidget(gEarthWidget);
572
#endif
pixhawk's avatar
pixhawk committed
573 574
    if (hudWidget) centerStack->addWidget(hudWidget);
    if (dataplotWidget) centerStack->addWidget(dataplotWidget);
575

576 577 578 579 580 581 582 583 584 585 586 587 588 589 590
}

void MainWindow::arrangeSlugsCenterStack()
{

  if (!centerStack) {
    qDebug() << "Center Stack not Created!";
    return;
  }

  if (linechartWidget) centerStack->addWidget(linechartWidget);


  if (hudWidget) centerStack->addWidget(hudWidget);

591 592
}

593 594
void MainWindow::configureWindowName()
{
pixhawk's avatar
pixhawk committed
595 596 597
    QList<QHostAddress> hostAddresses = QNetworkInterface::allAddresses();
    QString windowname = qApp->applicationName() + " " + qApp->applicationVersion();
    bool prevAddr = false;
598

pixhawk's avatar
pixhawk committed
599
    windowname.append(" (" + QHostInfo::localHostName() + ": ");
600

pixhawk's avatar
pixhawk committed
601 602 603 604 605 606 607 608 609 610
    for (int i = 0; i < hostAddresses.size(); i++)
    {
        // Exclude loopback IPv4 and all IPv6 addresses
        if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":"))
        {
            if(prevAddr) windowname.append("/");
            windowname.append(hostAddresses.at(i).toString());
            prevAddr = true;
        }
    }
611

pixhawk's avatar
pixhawk committed
612
    windowname.append(")");
613

pixhawk's avatar
pixhawk committed
614
    setWindowTitle(windowname);
615 616

#ifndef Q_WS_MAC
pixhawk's avatar
pixhawk committed
617
    //qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png"));
618 619 620
#endif
}

pixhawk's avatar
pixhawk committed
621
QStatusBar* MainWindow::createStatusBar()
pixhawk's avatar
pixhawk committed
622 623 624 625 626 627 628 629
{
    QStatusBar* bar = new QStatusBar();
    /* Add status fields and messages */
    /* Enable resize grip in the bottom right corner */
    bar->setSizeGripEnabled(true);
    return bar;
}

pixhawk's avatar
pixhawk committed
630
void MainWindow::startVideoCapture()
pixhawk's avatar
pixhawk committed
631 632 633 634 635 636 637 638 639 640 641
{
    QString format = "bmp";
    QString initialPath = QDir::currentPath() + tr("/untitled.") + format;

    QString screenFileName = QFileDialog::getSaveFileName(this, tr("Save As"),
                                                          initialPath,
                                                          tr("%1 Files (*.%2);;All Files (*)")
                                                          .arg(format.toUpper())
                                                          .arg(format));
    delete videoTimer;
    videoTimer = new QTimer(this);
642 643 644
    //videoTimer->setInterval(40);
    //connect(videoTimer, SIGNAL(timeout()), this, SLOT(saveScreen()));
    //videoTimer->stop();
pixhawk's avatar
pixhawk committed
645 646
}

pixhawk's avatar
pixhawk committed
647
void MainWindow::stopVideoCapture()
pixhawk's avatar
pixhawk committed
648 649 650 651 652 653
{
    videoTimer->stop();

    // TODO Convert raw images to PNG
}

pixhawk's avatar
pixhawk committed
654
void MainWindow::saveScreen()
pixhawk's avatar
pixhawk committed
655 656 657 658 659 660 661 662 663 664
{
    QPixmap window = QPixmap::grabWindow(this->winId());
    QString format = "bmp";

    if (!screenFileName.isEmpty())
    {
        window.save(screenFileName, format.toAscii());
    }
}

665 666 667 668 669 670
/**
 * Reload the style sheet from disk. The function tries to load "qgroundcontrol.css" from the application
 * directory (which by default does not exist). If it fails, it will load the bundled default CSS
 * from memory.
 * To customize the application, just create a qgroundcontrol.css file in the application directory
 */
pixhawk's avatar
pixhawk committed
671
void MainWindow::reloadStylesheet()
pixhawk's avatar
pixhawk committed
672 673
{
    // Load style sheet
674 675 676 677 678
    QFile* styleSheet = new QFile(QCoreApplication::applicationDirPath() + "/qgroundcontrol.css");
    if (!styleSheet->exists())
    {
        styleSheet = new QFile(":/images/style-mission.css");
    }
679 680
    if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text))
    {
681 682
        QString style = QString(styleSheet->readAll());
        style.replace("ICONDIR", QCoreApplication::applicationDirPath()+ "/images/");
pixhawk's avatar
pixhawk committed
683
        qApp->setStyleSheet(style);
684 685 686
    }
    else
    {
687
        qDebug() << "Style not set:" << styleSheet->fileName() << "opened: " << styleSheet->isOpen();
pixhawk's avatar
pixhawk committed
688
    }
689
    delete styleSheet;
pixhawk's avatar
pixhawk committed
690 691
}

pixhawk's avatar
pixhawk committed
692
void MainWindow::showStatusMessage(const QString& status, int timeout)
pixhawk's avatar
pixhawk committed
693
{
lm's avatar
lm committed
694 695
    Q_UNUSED(status);
    Q_UNUSED(timeout);
696
    //statusBar->showMessage(status, timeout);
pixhawk's avatar
pixhawk committed
697 698
}

699
void MainWindow::showStatusMessage(const QString& status)
pixhawk's avatar
pixhawk committed
700
{
lm's avatar
lm committed
701
    Q_UNUSED(status);
702
    //statusBar->showMessage(status, 5);
pixhawk's avatar
pixhawk committed
703 704 705 706 707 708
}

/**
* @brief Create all actions associated to the main window
*
**/
709
void MainWindow::connectCommonActions()
pixhawk's avatar
pixhawk committed
710
{
711

pixhawk's avatar
pixhawk committed
712 713 714 715 716 717
    // 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*)));

718
    // Unmanned System controls
pixhawk's avatar
pixhawk committed
719 720 721 722 723 724 725
    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()));

726
    // Views actions
727
    connect(ui.actionPilotsView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
728
    connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
729
    connect(ui.actionOperatorsView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
730

731 732
    connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
    connect(ui.actionReloadStyle, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
733

734
    // Help Actions
735 736 737
    connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
    connect(ui.actionDeveloper_Credits, SIGNAL(triggered()), this, SLOT(showCredits()));
    connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
738

739 740 741 742 743 744 745 746 747 748 749 750 751 752
}

void MainWindow::connectPxActions()
{

  ui.actionJoystickSettings->setVisible(true);

  // Joystick configuration
  connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));

}

void MainWindow::connectSlugsActions()
{
753

pixhawk's avatar
pixhawk committed
754 755
}

756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797
void MainWindow::showHelp()
{
    if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/user_guide")))
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Could not open help in browser");
        msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/user_guide in a browser.");
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

void MainWindow::showCredits()
{
    if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/credits")))
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Could not open credits in browser");
        msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/credits in a browser.");
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

void MainWindow::showRoadMap()
{
    if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/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();
    }
}

pixhawk's avatar
pixhawk committed
798
void MainWindow::configure()
pixhawk's avatar
pixhawk committed
799 800 801 802
{
    joystickWidget = new JoystickWidget(joystick, this);
}

pixhawk's avatar
pixhawk committed
803
void MainWindow::addLink()
pixhawk's avatar
pixhawk committed
804 805 806 807 808 809 810 811 812 813 814 815 816 817 818
{
    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!
}

pixhawk's avatar
pixhawk committed
819 820
void MainWindow::addLink(LinkInterface *link)
{
821
    LinkManager::instance()->addProtocol(link, mavlink);
pixhawk's avatar
pixhawk committed
822 823 824 825 826 827 828
    CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
    ui.menuNetwork->addAction(commWidget->getAction());

    // Special case for simulationlink
    MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
    if (sim)
    {
829
        //connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
pixhawk's avatar
pixhawk committed
830 831 832 833
        connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
    }
}

pixhawk's avatar
pixhawk committed
834
void MainWindow::UASCreated(UASInterface* uas)
pixhawk's avatar
pixhawk committed
835 836 837
{
    // Connect the UAS to the full user interface

838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869
    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
870 871
        if (debugConsoleDockWidget)
        {
pixhawk's avatar
pixhawk committed
872 873 874 875 876 877
            DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
            if (debugConsole)
            {
                connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
                        debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
            }
878
        }
879 880

        // Health / System status indicator
881 882
        if (infoDockWidget)
        {
pixhawk's avatar
pixhawk committed
883 884 885 886 887
            UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
            if (infoWidget)
            {
                infoWidget->addUAS(uas);
            }
888
        }
889 890

        // UAS List
891 892
        if (listDockWidget)
        {
pixhawk's avatar
pixhawk committed
893 894 895 896 897
            UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
            if (listWidget)
            {
                listWidget->addUAS(uas);
            }
898
        }
899 900 901 902 903 904 905 906

        // Camera view
        //camera->addUAS(uas);

        // Revalidate UI
        // TODO Stylesheet reloading should in theory not be necessary
        reloadStylesheet();

907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956
        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
//            if (slugsDataWidget) {
//              SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
//              if (dataWidget) {
//                SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
//                if (mav2) {
                  (dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget()))->addUAS(uas);
//                  //loadSlugsView();
//                  loadGlobalOperatorView();
//                }
//              }
//            }
          } break;
957
        }
958

959
        loadOperatorView();
960
    }
pixhawk's avatar
pixhawk committed
961 962
}

963 964 965
/**
 * Clears the current view completely
 */
pixhawk's avatar
pixhawk committed
966
void MainWindow::clearView()
pixhawk's avatar
pixhawk committed
967
{ 
968
    // Halt HUD central widget
969
    if (hudWidget) hudWidget->stop();
970

971 972
    // Disable linechart
    if (linechartWidget) linechartWidget->setActive(false);
973

974 975 976 977 978 979
    // Halt HDDs
    if (headDown1DockWidget)
    {
        HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown1DockWidget->widget() );
        if (hddWidget) hddWidget->stop();
    }
980

pixhawk's avatar
pixhawk committed
981
    if (headDown2DockWidget)
982 983 984 985
    {
        HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown2DockWidget->widget() );
        if (hddWidget) hddWidget->stop();
    }
986

987 988 989 990 991 992
    // Halt HSI
    if (hsiDockWidget)
    {
        HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
        if (hsi) hsi->stop();
    }
pixhawk's avatar
pixhawk committed
993

994 995 996 997 998 999 1000
    // Halt HUD if in docked widget mode
    if (headUpDockWidget)
    {
        HUD* hud = dynamic_cast<HUD*>( headUpDockWidget->widget() );
        if (hud) hud->stop();
    }

1001 1002
    // Remove all dock widgets from main window
    QObjectList childList( this->children() );
pixhawk's avatar
pixhawk committed
1003

1004 1005 1006
    QObjectList::iterator i;
    QDockWidget* dockWidget;
    for (i = childList.begin(); i != childList.end(); ++i)
pixhawk's avatar
pixhawk committed
1007
    {
1008 1009
        dockWidget = dynamic_cast<QDockWidget*>(*i);
        if (dockWidget)
pixhawk's avatar
pixhawk committed
1010
        {
1011 1012 1013 1014 1015
            // 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?
pixhawk's avatar
pixhawk committed
1016 1017 1018 1019
        }
    }
}

1020
void MainWindow::loadEngineerView()
lm's avatar
lm committed
1021
{
1022
  clearView();
lm's avatar
lm committed
1023

1024
  currentView = VIEW_ENGINEER;
lm's avatar
lm committed
1025

1026
  presentView();
lm's avatar
lm committed
1027 1028
}

1029
void MainWindow::loadOperatorView()
lm's avatar
lm committed
1030
{
1031 1032 1033
    clearView();

    currentView = VIEW_OPERATOR;
lm's avatar
lm committed
1034

1035
    presentView();
lm's avatar
lm committed
1036 1037
}

1038
void MainWindow::loadPilotView()
1039 1040
{
    clearView();
1041

1042 1043 1044
    currentView = VIEW_PILOT;

    presentView();
1045 1046
}

1047
void MainWindow::loadMAVLinkView()
1048 1049
{
    clearView();
pixhawk's avatar
pixhawk committed
1050

1051 1052 1053
    currentView = VIEW_MAVLINK;

    presentView();
1054 1055
}

1056
void MainWindow::presentView() {
pixhawk's avatar
pixhawk committed
1057 1058


1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069
#ifdef QGC_OSG_ENABLED
  // 3D map
  if (_3DWidget)
  {
      if (centerStack)
      {
          //map3DWidget->setActive(true);
          centerStack->setCurrentWidget(_3DWidget);
      }
  }
#endif
1070

1071
  qDebug() << "LC";
1072
  showTheCentralWidget(CENTRAL_LINECHART, currentView);
1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084
  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);
    }
  }
pixhawk's avatar
pixhawk committed
1085

1086

pixhawk's avatar
pixhawk committed
1087

1088 1089 1090
  // MAP
  qDebug() << "MAP";
  showTheCentralWidget(CENTRAL_MAP, currentView);
pixhawk's avatar
pixhawk committed
1091

1092 1093 1094
  // PROTOCOL
  qDebug() << "CP";
  showTheCentralWidget(CENTRAL_PROTOCOL, currentView);
pixhawk's avatar
pixhawk committed
1095

1096
  // HEAD UP DISPLAY
1097
  showTheCentralWidget(CENTRAL_HUD, currentView);
1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110
  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();
    }
  }
pixhawk's avatar
pixhawk committed
1111

1112
  // Show docked widgets based on current view and autopilot type
1113

1114 1115
  // UAS CONTROL
  showTheWidget(MENU_UAS_CONTROL, currentView);
1116

1117 1118
  // UAS LIST
  showTheWidget(MENU_UAS_LIST, currentView);
1119

1120 1121
  // WAYPOINT LIST
  showTheWidget(MENU_WAYPOINTS, currentView);
pixhawk's avatar
pixhawk committed
1122

1123 1124
  // UAS STATUS
  showTheWidget(MENU_STATUS, currentView);
1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139

  // 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);
1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155
  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();
        }
      }
  }

1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172

  // 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
1173
  showTheWidget(MENU_HSI, currentView);
1174 1175 1176
  if (hsiDockWidget)
  {
      HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
1177 1178
      if (hsi){
        if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
1179 1180 1181 1182
          hsi->start();
          addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
                        hsiDockWidget);
          hsiDockWidget->show();
1183 1184 1185 1186
        } else {
          hsi->stop();
          hsiDockWidget->hide();
        }
1187 1188 1189 1190
      }
  }

  // HEAD DOWN 1
1191
  showTheWidget(MENU_HDD_1, currentView);
1192 1193 1194
  if (headDown1DockWidget)
  {
      HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
1195 1196
      if (hdd) {
        if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool()) {
1197 1198 1199 1200
          addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
                        headDown1DockWidget);
          headDown1DockWidget->show();
          hdd->start();
1201 1202 1203 1204
        } else {
          headDown1DockWidget->hide();;
          hdd->stop();
        }
1205 1206 1207 1208
      }
  }

  // HEAD DOWN 2
1209
  showTheWidget(MENU_HDD_2, currentView);
1210 1211 1212
  if (headDown2DockWidget)
  {
      HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
1213 1214
      if (hdd){
        if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool()){
1215 1216 1217 1218
          addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
                        headDown2DockWidget);
          headDown2DockWidget->show();
          hdd->start();
1219 1220 1221 1222
        } else {
          headDown2DockWidget->hide();
          hdd->stop();
        }
1223 1224 1225 1226
      }
  }

  this->show();
1227

1228 1229
}

1230 1231 1232



1233
void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view){
1234 1235 1236 1237
  bool tempVisible;
  QWidget* tempWidget = dockWidgets[centralWidget];

  tempVisible =  settings.value(buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view)).toBool();
1238
  qDebug() << buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view) << tempVisible;
1239 1240 1241 1242 1243 1244 1245 1246 1247
  if (toolsMenuActions[centralWidget]){
    toolsMenuActions[centralWidget]->setChecked(tempVisible);
  }

  if (centerStack && tempWidget && tempVisible){
    centerStack->setCurrentWidget(tempWidget);
  }
}

1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261


/*
==========================================================
              Potentially Deprecated
==========================================================
*/

void MainWindow::loadPixhawkEngineerView()
{

}


1262 1263
void MainWindow::loadAllView()
{
1264 1265
    clearView();

1266 1267 1268 1269 1270 1271 1272 1273 1274
    if (headDown1DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
            headDown1DockWidget->show();
            hdd->start();
        }
1275

1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286
    }
    if (headDown2DockWidget)
    {
        HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
        if (hdd)
        {
            addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
            headDown2DockWidget->show();
            hdd->start();
        }
    }
1287 1288

    // UAS CONTROL
1289 1290 1291 1292 1293
    if (controlDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
        controlDockWidget->show();
    }
1294 1295

    // UAS LIST
1296 1297 1298 1299 1300
    if (listDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
        listDockWidget->show();
    }
1301 1302

    // UAS STATUS
1303 1304 1305 1306 1307
    if (infoDockWidget)
    {
        addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
        infoDockWidget->show();
    }
1308 1309

    // WAYPOINT LIST
1310 1311 1312 1313 1314
    if (waypointsDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
        waypointsDockWidget->show();
    }
1315 1316

    // DEBUG CONSOLE
1317 1318 1319 1320 1321
    if (debugConsoleDockWidget)
    {
        addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
        debugConsoleDockWidget->show();
    }
1322 1323

    // OBJECT DETECTION
1324 1325
    if (detectionDockWidget)
    {
pixhawk's avatar
pixhawk committed
1326 1327
        addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
        detectionDockWidget->show();
1328
    }
1329 1330

    // LINE CHART
1331 1332 1333 1334 1335 1336 1337 1338 1339
    if (linechartWidget)
    {
        QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
        if (centerStack)
        {
            linechartWidget->setActive(true);
            centerStack->setCurrentWidget(linechartWidget);
        }
    }
1340 1341

    // ONBOARD PARAMETERS
1342 1343 1344 1345 1346
    if (parametersDockWidget)
    {
        addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
        parametersDockWidget->show();
    }
1347 1348

    this->show();
1349 1350
}

pixhawk's avatar
pixhawk committed
1351
void MainWindow::loadWidgets()
pixhawk's avatar
pixhawk committed
1352
{
1353
    //loadOperatorView();
1354
    loadMAVLinkView();
pixhawk's avatar
pixhawk committed
1355 1356
    //loadPilotView();
}
1357

1358 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
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();

}
1543 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

/*
 ==================================
 ========== 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())

}

*/