Browse Source

Still working on having independent builds for each MAV, most of the work is done, only Central Widgets remain to be instantiated and menu-controlled based on the autopilot

QGC4.4
Mariano Lizarraga 15 years ago
parent
commit
8591b8550a
  1. 28
      src/comm/MAVLinkProtocol.cc
  2. 4
      src/uas/UAS.cc
  3. 5
      src/uas/UAS.h
  4. 4
      src/uas/UASInterface.h
  5. 5
      src/uas/UASManager.cc
  6. 1
      src/uas/UASManager.h
  7. 577
      src/ui/MainWindow.cc
  8. 29
      src/ui/MainWindow.h
  9. 13
      src/ui/MainWindow.ui

28
src/comm/MAVLinkProtocol.cc

@ -159,7 +159,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -159,7 +159,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
switch (heartbeat.autopilot)
{
case MAV_AUTOPILOT_GENERIC:
uas = new UAS(this, message.sysid);
// Set the autopilot type
uas->setAutopilotType((int)heartbeat.autopilot);
// Connect this robot to the UAS object
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), uas, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
break;
@ -167,6 +173,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -167,6 +173,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
// Fixme differentiate between quadrotor and coaxial here
PxQuadMAV* mav = new PxQuadMAV(this, message.sysid);
// Set the autopilot type
//mav->setAutopilotType((int)heartbeat.autopilot);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
@ -178,6 +188,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -178,6 +188,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
case MAV_AUTOPILOT_SLUGS:
{
SlugsMAV* mav = new SlugsMAV(this, message.sysid);
// Set the autopilot type
mav->setAutopilotType((int)heartbeat.autopilot);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
@ -189,6 +203,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -189,6 +203,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
case MAV_AUTOPILOT_ARDUPILOTMEGA:
{
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(this, message.sysid);
// Set the autopilot type
mav->setAutopilotType((int)heartbeat.autopilot);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
@ -202,11 +220,21 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -202,11 +220,21 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
break;
}
// Set the autopilot type
uas->setAutopilotType((int)heartbeat.autopilot);
// Make UAS aware that this link can be used to communicate with the actual robot
uas->addLink(link);
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uas);
qDebug() << "++===============================";
qDebug() << uas->getAutopilotType();
qDebug() << "++===============================";
}
// Only count message if UAS exists for this message

4
src/uas/UAS.cc

@ -44,12 +44,13 @@ This file is part of the QGROUNDCONTROL project @@ -44,12 +44,13 @@ This file is part of the QGROUNDCONTROL project
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(0),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
@ -153,6 +154,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -153,6 +154,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
emit systemTypeSet(this, type);
}
break;
case MAVLINK_MSG_ID_BOOT:
getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);

5
src/uas/UAS.h

@ -98,7 +98,7 @@ protected: @@ -98,7 +98,7 @@ protected:
quint64 startTime; ///< The time the UAS was switched on
CommStatus commStatus; ///< Communication status
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
int autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
@ -165,7 +165,8 @@ protected: @@ -165,7 +165,8 @@ protected:
public:
UASWaypointManager &getWaypointManager(void) { return waypointManager; }
int getSystemType();
unsigned char getAutopilotType() {return autopilot;}
int getAutopilotType() {return autopilot;}
void setAutopilotType(int apType) { autopilot = apType;}
public slots:
/** @brief Launches the system **/

4
src/uas/UASInterface.h

@ -157,7 +157,9 @@ public: @@ -157,7 +157,9 @@ public:
return color;
}
virtual unsigned char getAutopilotType() = 0;
virtual int getAutopilotType() = 0;
virtual void setAutopilotType(int apType)= 0;
public slots:
/** @brief Launches the system/Liftof **/

5
src/uas/UASManager.cc

@ -96,6 +96,11 @@ UASInterface* UASManager::getActiveUAS() @@ -96,6 +96,11 @@ UASInterface* UASManager::getActiveUAS()
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
UASInterface* UASManager::silentGetActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
bool UASManager::launchActiveUAS()
{
// If the active UAS is set, execute command

1
src/uas/UASManager.h

@ -57,6 +57,7 @@ public: @@ -57,6 +57,7 @@ public:
* @return NULL pointer if no UAS exists, active UAS else
**/
UASInterface* getActiveUAS();
UASInterface* silentGetActiveUAS();
/**
* @brief Get the UAS with this id
*

577
src/ui/MainWindow.cc

@ -47,6 +47,7 @@ @@ -47,6 +47,7 @@
MainWindow::MainWindow(QWidget *parent) :
QMainWindow(parent),
toolsMenuActions(),
currentView(VIEW_MAVLINK),
settings()
{
this->hide();
@ -76,8 +77,8 @@ MainWindow::MainWindow(QWidget *parent) : @@ -76,8 +77,8 @@ MainWindow::MainWindow(QWidget *parent) :
// Create actions
connectCommonActions();
// Load widgets and show application windowa
loadWidgets();
// Load mavlink view as default widget set
loadMAVLinkView();
// Adjust the size
adjustSize();
@ -120,7 +121,11 @@ void MainWindow::buildCommonWidgets() @@ -120,7 +121,11 @@ void MainWindow::buildCommonWidgets()
// Center widgets
mapWidget = new MapWidget(this);
addToCentralWidgetsMenu (mapWidget, "Maps", SLOT(showCentralWidget()),CENTRAL_MAP);
protocolWidget = new XMLCommProtocolWidget(this);
addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL);
}
void MainWindow::buildPxWidgets()
@ -231,9 +236,76 @@ void MainWindow::buildSlugsWidgets() @@ -231,9 +236,76 @@ void MainWindow::buildSlugsWidgets()
addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
}
/**
* Connect the signals and slots of the common window widgets
*/
void MainWindow::addToCentralWidgetsMenu ( QWidget* widget,
const QString title,
const char * slotName,
TOOLS_WIDGET_NAMES centralWidget){
QAction* tempAction;
// Add the separator that will separate tools from central Widgets
if (!toolsMenuActions[CENTRAL_SEPARATOR]){
tempAction = ui.menuTools->addSeparator();
toolsMenuActions[CENTRAL_SEPARATOR] = tempAction;
}
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);
} else {
tempAction->setChecked(settings.value(chKey).toBool());
}
// 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;
if (senderAction && dockWidgets[tool]){
// uncheck all central widget actions
QHashIterator<int, QAction*> i(toolsMenuActions);
while (i.hasNext()) {
i.next();
if (i.value()->data().toInt() >= 255){
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
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);
}
}
void MainWindow::addToToolsMenu ( QWidget* widget,
const QString title,
@ -242,7 +314,15 @@ void MainWindow::addToToolsMenu ( QWidget* widget, @@ -242,7 +314,15 @@ void MainWindow::addToToolsMenu ( QWidget* widget,
Qt::DockWidgetArea location){
QAction* tempAction;
QString posKey, chKey;
tempAction = ui.menuTools->addAction(title);
if (toolsMenuActions[CENTRAL_SEPARATOR]){
tempAction = new QAction(title, this);
ui.menuTools->insertAction(toolsMenuActions[CENTRAL_SEPARATOR],
tempAction);
} else {
tempAction = ui.menuTools->addAction(title);
}
tempAction->setCheckable(true);
tempAction->setData(tool);
@ -250,9 +330,7 @@ void MainWindow::addToToolsMenu ( QWidget* widget, @@ -250,9 +330,7 @@ void MainWindow::addToToolsMenu ( QWidget* widget,
toolsMenuActions[tool] = tempAction;
dockWidgets[tool] = widget;
// Based on Settings check/uncheck
// Postion key = menu/widget/position/pos_value
posKey = buildMenuKey (SUB_SECTION_LOCATION,tool);
posKey = buildMenuKey (SUB_SECTION_LOCATION,tool, currentView);
if (!settings.contains(posKey)){
settings.setValue(posKey,location);
@ -261,8 +339,7 @@ void MainWindow::addToToolsMenu ( QWidget* widget, @@ -261,8 +339,7 @@ void MainWindow::addToToolsMenu ( QWidget* widget,
dockWidgetLocations[tool] = static_cast <Qt::DockWidgetArea> (settings.value(posKey).toInt());
}
// Checked key = menu/widget/checked/pos_value
chKey = buildMenuKey(SUB_SECTION_CHECKED,tool);
chKey = buildMenuKey(SUB_SECTION_CHECKED,tool, currentView);
if (!settings.contains(chKey)){
settings.setValue(chKey,false);
@ -282,8 +359,17 @@ void MainWindow::addToToolsMenu ( QWidget* widget, @@ -282,8 +359,17 @@ void MainWindow::addToToolsMenu ( QWidget* widget,
}
QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES tool){
return (QString::number(SECTION_MENU) + "/" +
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) + "/" +
QString::number(tool) + "/" +
QString::number(section) + "/" );
}
@ -300,7 +386,7 @@ void MainWindow::showToolWidget(){ @@ -300,7 +386,7 @@ void MainWindow::showToolWidget(){
} else {
removeDockWidget(static_cast <QDockWidget *>(dockWidgets[tool]));
}
QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(tool));
QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(tool), currentView);
settings.setValue(chKey,temp->isChecked());
}
}
@ -339,15 +425,16 @@ void MainWindow::updateLocationSettings (Qt::DockWidgetArea location){ @@ -339,15 +425,16 @@ void MainWindow::updateLocationSettings (Qt::DockWidgetArea location){
while (i.hasNext()) {
i.next();
if ((static_cast <QDockWidget *>(dockWidgets[i.key()])) == temp){
QString posKey = buildMenuKey (SUB_SECTION_LOCATION,static_cast<TOOLS_WIDGET_NAMES>(i.key()));
QString posKey = buildMenuKey (SUB_SECTION_LOCATION,static_cast<TOOLS_WIDGET_NAMES>(i.key()), currentView);
settings.setValue(posKey,location);
break;
}
}
}
/**
* Connect the signals and slots of the common window widgets
*/
void MainWindow::connectCommonWidgets()
{
if (infoDockWidget && infoDockWidget->widget())
@ -362,16 +449,9 @@ void MainWindow::connectCommonWidgets() @@ -362,16 +449,9 @@ void MainWindow::connectCommonWidgets()
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)));
}
}
@ -582,8 +662,6 @@ void MainWindow::showStatusMessage(const QString& status) @@ -582,8 +662,6 @@ void MainWindow::showStatusMessage(const QString& status)
* @brief Create all actions associated to the main window
*
**/
void MainWindow::connectCommonActions()
{
@ -602,9 +680,9 @@ void MainWindow::connectCommonActions() @@ -602,9 +680,9 @@ void MainWindow::connectCommonActions()
connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS()));
// Views actions
connect(ui.actionFlightView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
connect(ui.actionPilotsView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
connect(ui.actionCalibrationView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
connect(ui.actionOperatorsView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
connect(ui.actionReloadStyle, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
@ -844,21 +922,25 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -844,21 +922,25 @@ void MainWindow::UASCreated(UASInterface* uas)
*/
void MainWindow::clearView()
{
// Halt HUD
// Halt HUD central widget
if (hudWidget) hudWidget->stop();
// Disable linechart
if (linechartWidget) linechartWidget->setActive(false);
// Halt HDDs
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)
{
@ -866,6 +948,13 @@ void MainWindow::clearView() @@ -866,6 +948,13 @@ void MainWindow::clearView()
if (hsi) hsi->stop();
}
// Halt HUD if in docked widget mode
if (headUpDockWidget)
{
HUD* hud = dynamic_cast<HUD*>( headUpDockWidget->widget() );
if (hud) hud->stop();
}
// Remove all dock widgets from main window
QObjectList childList( this->children() );
@ -955,80 +1044,7 @@ void MainWindow::loadSlugsView() @@ -955,80 +1044,7 @@ void MainWindow::loadSlugsView()
void MainWindow::loadPixhawkEngineerView()
{
clearView();
// Engineer view, used in EMAV2009
#ifdef QGC_OSG_ENABLED
// 3D map
if (_3DWidget)
{
if (centerStack)
{
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(_3DWidget);
}
}
#else
if (centerStack && linechartWidget){
centerStack->addWidget(linechartWidget);
}
#endif
// UAS CONTROL
if (controlDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// UAS LIST
if (listDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS
if (infoDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE
if (debugConsoleDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show();
}
void MainWindow::loadDataView()
@ -1060,160 +1076,12 @@ void MainWindow::loadDataView(QString fileName) @@ -1060,160 +1076,12 @@ void MainWindow::loadDataView(QString fileName)
}
}
void MainWindow::loadPilotView()
{
clearView();
// HEAD UP DISPLAY
if (hudWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(hudWidget);
hudWidget->start();
}
}
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*)));
if (headDown1DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
if (hdd)
{
addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
headDown1DockWidget->show();
hdd->start();
}
}
if (headDown2DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
if (hdd)
{
addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
headDown2DockWidget->show();
hdd->start();
}
}
this->show();
}
void MainWindow::loadOperatorView()
{
clearView();
// MAP
if (mapWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(mapWidget);
}
}
// UAS CONTROL
if (controlDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST
if (listDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS
if (infoDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
hsi->start();
}
}
// OBJECT DETECTION
if (detectionDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
detectionDockWidget->show();
}
// PROCESS CONTROL
if (watchdogControlDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
watchdogControlDockWidget->show();
}
this->show();
}
void MainWindow::loadSlugsEngineerView()
{
clearView();
// MAP
if (mapWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(mapWidget);
}
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// Slugs Data View
if (slugsDataWidget)
{
addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget);
slugsDataWidget->show();
}
// Slugs PID Tunning
if (slugsPIDControlWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget);
slugsPIDControlWidget->show();
}
// Slug Camera Control
if (slugsCamControlWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
slugsCamControlWidget->show();
}
}
@ -1377,63 +1245,184 @@ void MainWindow::load3DView() @@ -1377,63 +1245,184 @@ void MainWindow::load3DView()
void MainWindow::loadEngineerView()
{
clearView();
currentView = VIEW_ENGINEER;
presentView();
}
void MainWindow::loadOperatorView()
{
clearView();
// If there is no mav dont siwtch view
int selector = (UASManager::instance()->getActiveUAS())?
UASManager::instance()->getActiveUAS()->getAutopilotType() :
255;
switch (selector){
case (MAV_AUTOPILOT_GENERIC):
case (MAV_AUTOPILOT_ARDUPILOTMEGA):
case (MAV_AUTOPILOT_PIXHAWK):
loadPixhawkEngineerView();
break;
case (MAV_AUTOPILOT_SLUGS):
loadSlugsEngineerView();
break;
}
this->show();
currentView = VIEW_OPERATOR;
presentView();
}
void MainWindow::loadPilotView()
{
clearView();
currentView = VIEW_PILOT;
presentView();
}
void MainWindow::loadMAVLinkView()
{
clearView();
if (protocolWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(protocolWidget);
}
}
currentView = VIEW_MAVLINK;
presentView();
}
void MainWindow::presentView() {
#ifdef QGC_OSG_ENABLED
// 3D map
if (_3DWidget)
{
if (centerStack)
{
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(_3DWidget);
}
}
#else
showCentralWidget(CENTRAL_LINECHART, currentView);
// TODO: Refactor this code to single function calls
#endif
showTheWidget(MENU_UAS_CONTROL);
// MAP
showCentralWidget(CENTRAL_MAP, currentView);
showTheWidget(MENU_UAS_LIST);
// PROTOCOL
showCentralWidget(CENTRAL_PROTOCOL, currentView);
showTheWidget(MENU_WAYPOINTS);
// HEAD UP DISPLAY
if (hudWidget &&
settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
if (centerStack)
{
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(hudWidget);
hudWidget->start();
}
}
showTheWidget(MENU_STATUS);
// Show docked widgets based on current view and autopilot type
showTheWidget(MENU_DEBUG_CONSOLE);
// UAS CONTROL
showTheWidget(MENU_UAS_CONTROL, currentView);
// UAS LIST
showTheWidget(MENU_UAS_LIST, currentView);
// WAYPOINT LIST
showTheWidget(MENU_WAYPOINTS, currentView);
// UAS STATUS
showTheWidget(MENU_STATUS, currentView);
// 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);
// 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
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi &&
settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool())
{
hsi->start();
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
hsiDockWidget);
hsiDockWidget->show();
}
}
// HEAD DOWN 1
if (headDown1DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
if (hdd &&
settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool())
{
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
headDown1DockWidget);
headDown1DockWidget->show();
hdd->start();
}
}
// HEAD DOWN 2
if (headDown2DockWidget)
{
HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
if (hdd &&
settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool())
{
addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
headDown2DockWidget);
headDown2DockWidget->show();
hdd->start();
}
}
this->show();
this->show();
}
void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget){
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)).toBool();
tempLocation = static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,widget)).toInt());
tempVisible = settings.value(buildMenuKey (SUB_SECTION_CHECKED,widget,view)).toBool();
if (toolsMenuActions[widget]){
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);
@ -1441,6 +1430,22 @@ void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget){ @@ -1441,6 +1430,22 @@ void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget){
}
}
void MainWindow::showCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view){
bool tempVisible;
QWidget* tempWidget = dockWidgets[centralWidget];
tempVisible = settings.value(buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view)).toBool();
if (toolsMenuActions[centralWidget]){
toolsMenuActions[centralWidget]->setChecked(tempVisible);
}
if (centerStack && tempWidget && tempVisible){
centerStack->setCurrentWidget(tempWidget);
}
}
void MainWindow::loadAllView()
{
clearView();

29
src/ui/MainWindow.h

@ -146,11 +146,14 @@ public slots: @@ -146,11 +146,14 @@ public slots:
void loadPixhawkEngineerView();
void loadSlugsEngineerView();
void presentView();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
void showToolWidget();
void showCentralWidget();
void updateVisibilitySettings (bool vis);
void updateLocationSettings (Qt::DockWidgetArea location);
protected:
@ -179,7 +182,7 @@ protected: @@ -179,7 +182,7 @@ protected:
MENU_SLUGS_PID,
MENU_SLUGS_HIL,
MENU_SLUGS_CAMERA,
CENTRAL_LINECHART = 255, // Separation from dockwidgets and central widgets
CENTRAL_LINECHART = 255, // do not change
CENTRAL_PROTOCOL,
CENTRAL_MAP,
CENTRAL_3D_LOCAL,
@ -187,18 +190,22 @@ protected: @@ -187,18 +190,22 @@ protected:
CENTRAL_GOOGLE_EARTH,
CENTRAL_HUD,
CENTRAL_DATA_PLOT,
CENTRAL_SEPARATOR,
}TOOLS_WIDGET_NAMES;
typedef enum _SETTINGS_SECTIONS {
SECTION_MENU,
VIEW_ENGINEER,
VIEW_OPERATOR,
VIEW_CALIBRATION,
VIEW_MAVLINK,
SUB_SECTION_CHECKED,
SUB_SECTION_LOCATION,
} SETTINGS_SECTIONS;
typedef enum _VIEW_SECTIONS {
VIEW_ENGINEER,
VIEW_OPERATOR,
VIEW_PILOT,
VIEW_MAVLINK,
} VIEW_SECTIONS;
QHash<int, QAction*> toolsMenuActions; // Holds ptr to the Menu Actions
QHash<int, QWidget*> dockWidgets; // Holds ptr to the Actual Dock widget
@ -206,9 +213,11 @@ protected: @@ -206,9 +213,11 @@ protected:
void addToToolsMenu (QWidget* widget, const QString title, const char * slotName, TOOLS_WIDGET_NAMES tool, Qt::DockWidgetArea location);
void showTheWidget (TOOLS_WIDGET_NAMES widget);
void showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view = VIEW_MAVLINK);
void showCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view);
void addToCentralWidgetsMenu ( QWidget* widget, const QString title,const char * slotName, TOOLS_WIDGET_NAMES centralWidget);
int currentView;
VIEW_SECTIONS currentView;
int aboutToQuit;
//QHash<int, QString> settingsSections;
@ -250,7 +259,9 @@ protected: @@ -250,7 +259,9 @@ protected:
// Center widgets
QPointer<Linecharts> linechartWidget;
QPointer<HUD> hudWidget;
QPointer<MapWidget> mapWidget;
QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget;
@ -273,7 +284,9 @@ protected: @@ -273,7 +284,9 @@ protected:
QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> slugsDataWidget;
@ -304,7 +317,7 @@ protected: @@ -304,7 +317,7 @@ protected:
private:
Ui::MainWindow ui;
QString buildMenuKey (SETTINGS_SECTIONS section , TOOLS_WIDGET_NAMES tool);
QString buildMenuKey (SETTINGS_SECTIONS section , TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view);
};

13
src/ui/MainWindow.ui

@ -80,7 +80,6 @@ @@ -80,7 +80,6 @@
<property name="title">
<string>Tools</string>
</property>
<addaction name="separator"/>
</widget>
<widget class="QMenu" name="menuHelp">
<property name="title">
@ -94,9 +93,9 @@ @@ -94,9 +93,9 @@
<property name="title">
<string>Perspectives</string>
</property>
<addaction name="actionFlightView"/>
<addaction name="actionOperatorsView"/>
<addaction name="actionEngineersView"/>
<addaction name="actionCalibrationView"/>
<addaction name="actionPilotsView"/>
<addaction name="separator"/>
<addaction name="actionMavlinkView"/>
<addaction name="actionReloadStyle"/>
@ -393,13 +392,13 @@ @@ -393,13 +392,13 @@
<string>Developer Credits</string>
</property>
</action>
<action name="actionFlightView">
<action name="actionOperatorsView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/weather-overcast.svg</normaloff>:/images/status/weather-overcast.svg</iconset>
</property>
<property name="text">
<string>Flight</string>
<string>Operator</string>
</property>
</action>
<action name="actionEngineersView">
@ -429,13 +428,13 @@ @@ -429,13 +428,13 @@
<string>Reload Style</string>
</property>
</action>
<action name="actionCalibrationView">
<action name="actionPilotsView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/network-wireless-encrypted.svg</normaloff>:/images/status/network-wireless-encrypted.svg</iconset>
</property>
<property name="text">
<string>Calibration</string>
<string>Pilot</string>
</property>
</action>
</widget>

Loading…
Cancel
Save