Commit bb1f8fe6 authored by Michael Schulz's avatar Michael Schulz

Fixed memory leak with dock widgets in MainWindow

parent 723118a2
...@@ -108,6 +108,7 @@ MainWindow::~MainWindow() ...@@ -108,6 +108,7 @@ MainWindow::~MainWindow()
void MainWindow::buildWidgets() void MainWindow::buildWidgets()
{ {
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList(); QStringList* acceptList = new QStringList();
acceptList->append("roll IMU"); acceptList->append("roll IMU");
acceptList->append("pitch IMU"); acceptList->append("pitch IMU");
...@@ -116,50 +117,93 @@ void MainWindow::buildWidgets() ...@@ -116,50 +117,93 @@ void MainWindow::buildWidgets()
acceptList->append("pitchspeed IMU"); acceptList->append("pitchspeed IMU");
acceptList->append("yawspeed IMU"); acceptList->append("yawspeed IMU");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList(); QStringList* acceptList2 = new QStringList();
acceptList2->append("Battery"); acceptList2->append("Battery");
acceptList2->append("Pressure"); acceptList2->append("Pressure");
//TODO: move protocol outside UI
mavlink = new MAVLinkProtocol(); mavlink = new MAVLinkProtocol();
linechart = new Linecharts(this);
control = new UASControlWidget(this); // Center widgets
list = new UASListWidget(this); linechartWidget = new Linecharts(this);
waypoints = new WaypointList(this, NULL); hudWidget = new HUD(640, 480, this);
info = new UASInfoWidget(this); mapWidget = new MapWidget(this);
detection = new ObjectDetectionView("images/patterns", this); protocolWidget = new XMLCommProtocolWidget(this);
hud = new HUD(640, 480, this); dataplotWidget = new QGCDataPlot2D(this);
debugConsole= new DebugConsole(this);
map = new MapWidget(this); // Dock widgets
protocol = new XMLCommProtocolWidget(this); controlDockWidget = new QDockWidget(tr("Control"), this);
parameters = new ParameterInterface(this); controlDockWidget->setWidget( new UASControlWidget(this) );
watchdogControl = new WatchdogControl(this);
hsi = new HSIDisplay(this); listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
headDown1 = new HDDisplay(acceptList, this); listDockWidget->setWidget( new UASListWidget(this) );
headDown2 = new HDDisplay(acceptList2, 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) );
// Dialogue widgets
//FIXME: free memory in destructor
joystick = new JoystickInput(); joystick = new JoystickInput();
dataplot = new QGCDataPlot2D(this);
rcView = new QGCRemoteControlView(this);
} }
void MainWindow::connectWidgets() void MainWindow::connectWidgets()
{ {
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), linechart, SLOT(addSystem(UASInterface*))); if (linechartWidget)
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), linechart, SLOT(selectSystem(int))); {
connect(linechart, SIGNAL(logfileWritten(QString)), this, SLOT(loadDataView(QString))); connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
connect(mavlink, SIGNAL(receiveLossChanged(int, float)), info, SLOT(updateSendLoss(int, float))); 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)));
}
} }
void MainWindow::arrangeCenterStack() void MainWindow::arrangeCenterStack()
{ {
centerStack = new QStackedWidget(this); QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return;
centerStack->addWidget(linechart); if (linechartWidget) centerStack->addWidget(linechartWidget);
centerStack->addWidget(protocol); if (protocolWidget) centerStack->addWidget(protocolWidget);
centerStack->addWidget(map); if (mapWidget) centerStack->addWidget(mapWidget);
centerStack->addWidget(hud); if (hudWidget) centerStack->addWidget(hudWidget);
centerStack->addWidget(dataplot); if (dataplotWidget) centerStack->addWidget(dataplotWidget);
setCentralWidget(centerStack); setCentralWidget(centerStack);
} }
...@@ -425,13 +469,35 @@ void MainWindow::UASCreated(UASInterface* uas) ...@@ -425,13 +469,35 @@ void MainWindow::UASCreated(UASInterface* uas)
ui.menuConnected_Systems->addAction(icon, tr("Select %1 for control").arg(uas->getUASName()), uas, SLOT(setSelected())); ui.menuConnected_Systems->addAction(icon, tr("Select %1 for control").arg(uas->getUASName()), uas, SLOT(setSelected()));
// FIXME Should be not inside the mainwindow // FIXME Should be not inside the mainwindow
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), debugConsole, SLOT(receiveTextMessage(int,int,int,QString))); if (debugConsoleDockWidget)
{
DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
if (debugConsole)
{
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
}
}
// Health / System status indicator // Health / System status indicator
info->addUAS(uas); if (infoDockWidget)
{
UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
if (infoWidget)
{
infoWidget->addUAS(uas);
}
}
// UAS List // UAS List
list->addUAS(uas); if (listDockWidget)
{
UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
if (listWidget)
{
listWidget->addUAS(uas);
}
}
// Camera view // Camera view
//camera->addUAS(uas); //camera->addUAS(uas);
...@@ -455,27 +521,42 @@ void MainWindow::UASCreated(UASInterface* uas) ...@@ -455,27 +521,42 @@ void MainWindow::UASCreated(UASInterface* uas)
void MainWindow::clearView() void MainWindow::clearView()
{ {
// Halt HUD // Halt HUD
hud->stop(); if (hudWidget) hudWidget->stop();
linechart->setActive(false); // Disable linechart
headDown1->stop(); if (linechartWidget) linechartWidget->setActive(false);
headDown2->stop(); // Halt HDDs
hsi->stop(); if (headDown1DockWidget)
{
HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown1DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
if (headDown2DockWidget)
{
HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown2DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
// Halt HSI
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi) hsi->stop();
}
// Remove all dock widgets // Remove all dock widgets from main window
QList<QObject*> list = this->children(); QObjectList childList( this->children() );
QList<QObject*>::iterator i; QObjectList::iterator i;
for (i = list.begin(); i != list.end(); ++i) QDockWidget* dockWidget;
for (i = childList.begin(); i != childList.end(); ++i)
{ {
QDockWidget* widget = dynamic_cast<QDockWidget*>(*i); dockWidget = dynamic_cast<QDockWidget*>(*i);
if (widget) if (dockWidget)
{ {
// Hide widgets // Remove dock widget from main window
QWidget* childWidget = dynamic_cast<QWidget*>(widget->widget()); this->removeDockWidget(dockWidget);
if (childWidget) childWidget->setVisible(false); // Deletion of dockWidget would also delete all child
// Remove dock widget // widgets of dockWidget
this->removeDockWidget(widget); // Is there a way to unset a widget from QDockWidget?
//delete widget;
} }
} }
} }
...@@ -486,45 +567,69 @@ void MainWindow::loadSlugsView() ...@@ -486,45 +567,69 @@ void MainWindow::loadSlugsView()
// Engineer view, used in EMAV2009 // Engineer view, used in EMAV2009
// LINE CHART // LINE CHART
linechart->setActive(true); if (linechartWidget)
centerStack->setCurrentWidget(linechart); {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
// UAS CONTROL // UAS CONTROL
QDockWidget* container1 = new QDockWidget(tr("Control"), this); if (controlDockWidget)
container1->setWidget(control); {
addDockWidget(Qt::LeftDockWidgetArea, container1); addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST // UAS LIST
QDockWidget* container4 = new QDockWidget(tr("Unmanned Systems"), this); if (listDockWidget)
container4->setWidget(list); {
addDockWidget(Qt::BottomDockWidgetArea, container4); addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS // UAS STATUS
QDockWidget* container3 = new QDockWidget(tr("Status Details"), this); if (infoDockWidget)
container3->setWidget(info); {
addDockWidget(Qt::LeftDockWidgetArea, container3); addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR // HORIZONTAL SITUATION INDICATOR
QDockWidget* container6 = new QDockWidget(tr("Horizontal Situation Indicator"), this); if (hsiDockWidget)
container6->setWidget(hsi); {
hsi->start(); HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
addDockWidget(Qt::LeftDockWidgetArea, container6); if (hsi)
{
hsi->start();
addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// WAYPOINT LIST // WAYPOINT LIST
QDockWidget* container5 = new QDockWidget(tr("Waypoint List"), this); if (waypointsDockWidget)
container5->setWidget(waypoints); {
addDockWidget(Qt::BottomDockWidgetArea, container5); addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE // DEBUG CONSOLE
QDockWidget* container7 = new QDockWidget(tr("Communication Console"), this); if (debugConsoleDockWidget)
container7->setWidget(debugConsole); {
addDockWidget(Qt::BottomDockWidgetArea, container7); addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
// ONBOARD PARAMETERS // ONBOARD PARAMETERS
QDockWidget* containerParams = new QDockWidget(tr("Onboard Parameters"), this); if (parametersDockWidget)
containerParams->setWidget(parameters); {
addDockWidget(Qt::RightDockWidgetArea, containerParams); addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show(); this->show();
} }
...@@ -535,44 +640,64 @@ void MainWindow::loadPixhawkView() ...@@ -535,44 +640,64 @@ void MainWindow::loadPixhawkView()
// Engineer view, used in EMAV2009 // Engineer view, used in EMAV2009
// LINE CHART // LINE CHART
linechart->setActive(true); if (linechartWidget)
centerStack->setCurrentWidget(linechart); {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
// UAS CONTROL // UAS CONTROL
QDockWidget* container1 = new QDockWidget(tr("Control"), this); if (controlDockWidget)
container1->setWidget(control); {
addDockWidget(Qt::LeftDockWidgetArea, container1); addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST // UAS LIST
QDockWidget* container4 = new QDockWidget(tr("Unmanned Systems"), this); if (listDockWidget)
container4->setWidget(list); {
addDockWidget(Qt::BottomDockWidgetArea, container4); addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS // UAS STATUS
QDockWidget* container3 = new QDockWidget(tr("Status Details"), this); if (infoDockWidget)
container3->setWidget(info); {
addDockWidget(Qt::LeftDockWidgetArea, container3); addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST // WAYPOINT LIST
QDockWidget* container5 = new QDockWidget(tr("Waypoint List"), this); if (waypointsDockWidget)
container5->setWidget(waypoints); {
addDockWidget(Qt::BottomDockWidgetArea, container5); addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE // DEBUG CONSOLE
QDockWidget* container7 = new QDockWidget(tr("Communication Console"), this); if (debugConsoleDockWidget)
container7->setWidget(debugConsole); {
addDockWidget(Qt::BottomDockWidgetArea, container7); addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
// RADIO CONTROL VIEW // RADIO CONTROL VIEW
QDockWidget* rcContainer = new QDockWidget(tr("Radio Control"), this); if (rcViewDockWidget)
rcContainer->setWidget(rcView); {
addDockWidget(Qt::BottomDockWidgetArea, rcContainer); addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
// ONBOARD PARAMETERS // ONBOARD PARAMETERS
QDockWidget* containerParams = new QDockWidget(tr("Onboard Parameters"), this); if (parametersDockWidget)
containerParams->setWidget(parameters); {
addDockWidget(Qt::RightDockWidgetArea, containerParams); addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show(); this->show();
} }
...@@ -580,14 +705,30 @@ void MainWindow::loadPixhawkView() ...@@ -580,14 +705,30 @@ void MainWindow::loadPixhawkView()
void MainWindow::loadDataView() void MainWindow::loadDataView()
{ {
clearView(); clearView();
centerStack->setCurrentWidget(dataplot);
// DATAPLOT
if (dataplotWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
centerStack->setCurrentWidget(dataplotWidget);
}
} }
void MainWindow::loadDataView(QString fileName) void MainWindow::loadDataView(QString fileName)
{ {
clearView(); clearView();
centerStack->setCurrentWidget(dataplot);
dataplot->loadFile(fileName); // DATAPLOT
if (dataplotWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(dataplotWidget);
dataplotWidget->loadFile(fileName);
}
}
} }
void MainWindow::loadPilotView() void MainWindow::loadPilotView()
...@@ -595,20 +736,38 @@ void MainWindow::loadPilotView() ...@@ -595,20 +736,38 @@ void MainWindow::loadPilotView()
clearView(); clearView();
// HEAD UP DISPLAY // HEAD UP DISPLAY
centerStack->setCurrentWidget(hud); if (hudWidget)
hud->start(); {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(hudWidget);
hudWidget->start();
}
}
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*))); //connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*)));
QDockWidget* container1 = new QDockWidget(tr("Primary Flight Display"), this); if (headDown1DockWidget)
container1->setWidget(headDown1); {
addDockWidget(Qt::RightDockWidgetArea, container1); HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
if (hdd)
QDockWidget* container2 = new QDockWidget(tr("Payload Status"), this); {
container2->setWidget(headDown2); addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
addDockWidget(Qt::RightDockWidgetArea, container2); headDown1DockWidget->show();
hdd->start();
headDown1->start(); }
headDown2->start();
}
if (headDown2DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
if (hdd)
{
addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
headDown2DockWidget->show();
hdd->start();
}
}
this->show(); this->show();
} }
...@@ -618,43 +777,68 @@ void MainWindow::loadOperatorView() ...@@ -618,43 +777,68 @@ void MainWindow::loadOperatorView()
clearView(); clearView();
// MAP // MAP
centerStack->setCurrentWidget(map); if (mapWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(mapWidget);
}
}
// UAS CONTROL // UAS CONTROL
QDockWidget* container1 = new QDockWidget(tr("Control"), this); if (controlDockWidget)
container1->setWidget(control); {
addDockWidget(Qt::LeftDockWidgetArea, container1); addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST // UAS LIST
QDockWidget* container4 = new QDockWidget(tr("Unmanned Systems"), this); if (listDockWidget)
container4->setWidget(list); {
addDockWidget(Qt::BottomDockWidgetArea, container4); addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS // UAS STATUS
QDockWidget* container3 = new QDockWidget(tr("Status Details"), this); if (infoDockWidget)
container3->setWidget(info); {
addDockWidget(Qt::LeftDockWidgetArea, container3); addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST // WAYPOINT LIST
QDockWidget* container5 = new QDockWidget(tr("Waypoint List"), this); if (waypointsDockWidget)
container5->setWidget(waypoints); {
addDockWidget(Qt::BottomDockWidgetArea, container5); addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR // HORIZONTAL SITUATION INDICATOR
QDockWidget* container7 = new QDockWidget(tr("Horizontal Situation Indicator"), this); if (hsiDockWidget)
container7->setWidget(hsi); {
hsi->start(); HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
addDockWidget(Qt::BottomDockWidgetArea, container7); if (hsi)
{
addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
hsi->start();
}
}
// OBJECT DETECTION // OBJECT DETECTION
QDockWidget* container6 = new QDockWidget(tr("Object Recognition"), this); if (detectionDockWidget)
container6->setWidget(detection); {
addDockWidget(Qt::RightDockWidgetArea, container6); addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
detectionDockWidget->show();
}
// PROCESS CONTROL // PROCESS CONTROL
QDockWidget* pControl = new QDockWidget(tr("Process Control"), this); if (watchdogControlDockWidget)
pControl->setWidget(watchdogControl); {
addDockWidget(Qt::RightDockWidgetArea, pControl); addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
watchdogControlDockWidget->show();
}
this->show(); this->show();
} }
...@@ -663,8 +847,15 @@ void MainWindow::loadSettingsView() ...@@ -663,8 +847,15 @@ void MainWindow::loadSettingsView()
clearView(); clearView();
// LINE CHART // LINE CHART
linechart->setActive(true); if (linechartWidget)
centerStack->setCurrentWidget(linechart); {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
/* /*
// COMM XML // COMM XML
...@@ -673,9 +864,12 @@ void MainWindow::loadSettingsView() ...@@ -673,9 +864,12 @@ void MainWindow::loadSettingsView()
addDockWidget(Qt::LeftDockWidgetArea, container1);*/ addDockWidget(Qt::LeftDockWidgetArea, container1);*/
// ONBOARD PARAMETERS // ONBOARD PARAMETERS
QDockWidget* container6 = new QDockWidget(tr("Onboard Parameters"), this); if (parametersDockWidget)
container6->setWidget(parameters); {
addDockWidget(Qt::RightDockWidgetArea, container6); addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show(); this->show();
} }
...@@ -685,39 +879,57 @@ void MainWindow::loadEngineerView() ...@@ -685,39 +879,57 @@ void MainWindow::loadEngineerView()
// Engineer view, used in EMAV2009 // Engineer view, used in EMAV2009
// LINE CHART // LINE CHART
linechart->setActive(true); if (linechartWidget)
centerStack->setCurrentWidget(linechart); {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
// UAS CONTROL // UAS CONTROL
QDockWidget* container1 = new QDockWidget(tr("Control"), this); if (controlDockWidget)
container1->setWidget(control); {
addDockWidget(Qt::LeftDockWidgetArea, container1); addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST // UAS LIST
QDockWidget* container4 = new QDockWidget(tr("Unmanned Systems"), this); if (listDockWidget)
container4->setWidget(list); {
addDockWidget(Qt::BottomDockWidgetArea, container4); addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS // UAS STATUS
QDockWidget* container3 = new QDockWidget(tr("Status Details"), this); if (infoDockWidget)
container3->setWidget(info); {
addDockWidget(Qt::LeftDockWidgetArea, container3); addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST // WAYPOINT LIST
QDockWidget* container5 = new QDockWidget(tr("Waypoint List"), this); if (waypointsDockWidget)
container5->setWidget(waypoints); {
addDockWidget(Qt::BottomDockWidgetArea, container5); addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE // DEBUG CONSOLE
QDockWidget* container7 = new QDockWidget(tr("Communication Console"), this); if (debugConsoleDockWidget)
container7->setWidget(debugConsole); {
addDockWidget(Qt::BottomDockWidgetArea, container7); addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
// ONBOARD PARAMETERS // ONBOARD PARAMETERS
QDockWidget* containerParams = new QDockWidget(tr("Onboard Parameters"), this); if (parametersDockWidget)
containerParams->setWidget(parameters); {
addDockWidget(Qt::RightDockWidgetArea, containerParams); addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show(); this->show();
} }
...@@ -725,7 +937,16 @@ void MainWindow::loadEngineerView() ...@@ -725,7 +937,16 @@ void MainWindow::loadEngineerView()
void MainWindow::loadMAVLinkView() void MainWindow::loadMAVLinkView()
{ {
clearView(); clearView();
centerStack->setCurrentWidget(protocol);
if (protocolWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(protocolWidget);
}
}
this->show(); this->show();
} }
...@@ -733,55 +954,87 @@ void MainWindow::loadAllView() ...@@ -733,55 +954,87 @@ void MainWindow::loadAllView()
{ {
clearView(); clearView();
QDockWidget* containerPFD = new QDockWidget(tr("Primary Flight Display"), this); if (headDown1DockWidget)
containerPFD->setWidget(headDown1); {
addDockWidget(Qt::RightDockWidgetArea, containerPFD); HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
if (hdd)
QDockWidget* containerPayload = new QDockWidget(tr("Payload Status"), this); {
containerPayload->setWidget(headDown2); addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
addDockWidget(Qt::RightDockWidgetArea, containerPayload); headDown1DockWidget->show();
hdd->start();
headDown1->start(); }
headDown2->start();
}
if (headDown2DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
if (hdd)
{
addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
headDown2DockWidget->show();
hdd->start();
}
}
// UAS CONTROL // UAS CONTROL
QDockWidget* containerControl = new QDockWidget(tr("Control"), this); if (controlDockWidget)
containerControl->setWidget(control); {
addDockWidget(Qt::LeftDockWidgetArea, containerControl); addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST // UAS LIST
QDockWidget* containerUASList = new QDockWidget(tr("Unmanned Systems"), this); if (listDockWidget)
containerUASList->setWidget(list); {
addDockWidget(Qt::BottomDockWidgetArea, containerUASList); addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS // UAS STATUS
QDockWidget* containerStatus = new QDockWidget(tr("Status Details"), this); if (infoDockWidget)
containerStatus->setWidget(info); {
addDockWidget(Qt::LeftDockWidgetArea, containerStatus); addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST // WAYPOINT LIST
QDockWidget* containerWaypoints = new QDockWidget(tr("Waypoint List"), this); if (waypointsDockWidget)
containerWaypoints->setWidget(waypoints); {
addDockWidget(Qt::BottomDockWidgetArea, containerWaypoints); addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE // DEBUG CONSOLE
QDockWidget* containerComm = new QDockWidget(tr("Communication Console"), this); if (debugConsoleDockWidget)
containerComm->setWidget(debugConsole); {
addDockWidget(Qt::BottomDockWidgetArea, containerComm); addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
// OBJECT DETECTION // OBJECT DETECTION
QDockWidget* containerObjRec = new QDockWidget(tr("Object Recognition"), this); if (detectionDockWidget)
containerObjRec->setWidget(detection); {
addDockWidget(Qt::RightDockWidgetArea, containerObjRec); addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
detectionDockWidget->show();
}
// LINE CHART // LINE CHART
linechart->setActive(true); if (linechartWidget)
centerStack->setCurrentWidget(linechart); {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
// ONBOARD PARAMETERS // ONBOARD PARAMETERS
QDockWidget* containerParams = new QDockWidget(tr("Onboard Parameters"), this); if (parametersDockWidget)
containerParams->setWidget(parameters); {
addDockWidget(Qt::RightDockWidgetArea, containerParams); addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show(); this->show();
} }
......
...@@ -154,24 +154,26 @@ protected: ...@@ -154,24 +154,26 @@ protected:
LinkInterface* udpLink; LinkInterface* udpLink;
QSettings settings; QSettings settings;
UASControlWidget* control; // Center widgets
Linecharts* linechart; QPointer<Linecharts> linechartWidget;
UASInfoWidget* info; QPointer<HUD> hudWidget;
CameraView* camera; QPointer<MapWidget> mapWidget;
UASListWidget* list; QPointer<XMLCommProtocolWidget> protocolWidget;
WaypointList* waypoints; QPointer<QGCDataPlot2D> dataplotWidget;
ObjectDetectionView* detection; // Dock widgets
HUD* hud; QPointer<QDockWidget> controlDockWidget;
DebugConsole* debugConsole; QPointer<QDockWidget> infoDockWidget;
MapWidget* map; QPointer<QDockWidget> cameraDockWidget;
ParameterInterface* parameters; QPointer<QDockWidget> listDockWidget;
XMLCommProtocolWidget* protocol; QPointer<QDockWidget> waypointsDockWidget;
HDDisplay* headDown1; QPointer<QDockWidget> detectionDockWidget;
HDDisplay* headDown2; QPointer<QDockWidget> debugConsoleDockWidget;
WatchdogControl* watchdogControl; QPointer<QDockWidget> parametersDockWidget;
HSIDisplay* hsi; QPointer<QDockWidget> headDown1DockWidget;
QGCDataPlot2D* dataplot; QPointer<QDockWidget> headDown2DockWidget;
QGCRemoteControlView* rcView; QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
// Popup widgets // Popup widgets
JoystickWidget* joystickWidget; JoystickWidget* joystickWidget;
...@@ -187,9 +189,6 @@ protected: ...@@ -187,9 +189,6 @@ protected:
QAction* killUASAct; QAction* killUASAct;
QAction* simulateUASAct; QAction* simulateUASAct;
QDockWidget* controlDock;
QStackedWidget* centerStack;
LogCompressor* comp; LogCompressor* comp;
QString screenFileName; QString screenFileName;
QTimer* videoTimer; QTimer* videoTimer;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment