Browse Source

VERY UNSTABLE. Working on changing the way widgets are constructed and shown now based on the Detected autopilot. The basic scaffolding is in place still needs a lot of work.

QGC4.4
Mariano Lizarraga 14 years ago
parent
commit
9b61aeec32
  1. 2
      src/uas/UAS.cc
  2. 22
      src/uas/UAS.h
  3. 3
      src/uas/UASInterface.h
  4. 702
      src/ui/MainWindow.cc
  5. 46
      src/ui/MainWindow.h
  6. 68
      src/ui/MainWindow.ui
  7. 4
      src/ui/QGCRemoteControlView.cc

2
src/uas/UAS.cc

@ -49,6 +49,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), @@ -49,6 +49,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(0),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
@ -149,6 +150,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -149,6 +150,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (this->type != mavlink_msg_heartbeat_get_type(&message))
{
this->type = mavlink_msg_heartbeat_get_type(&message);
this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
emit systemTypeSet(this, type);
}
break;

22
src/uas/UAS.h

@ -79,25 +79,26 @@ public: @@ -79,25 +79,26 @@ public:
/** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks();
double getLocalX() const { return localX; };
double getLocalY() const { return localY; };
double getLocalZ() const { return localZ; };
double getLatitude() const { return latitude; };
double getLongitude() const { return longitude; };
double getAltitude() const { return altitude; };
double getLocalX() const { return localX; }
double getLocalY() const { return localY; }
double getLocalZ() const { return localZ; }
double getLatitude() const { return latitude; }
double getLongitude() const { return longitude; }
double getAltitude() const { return altitude; }
double getRoll() const { return roll; };
double getPitch() const { return pitch; };
double getYaw() const { return yaw; };
double getRoll() const { return roll; }
double getPitch() const { return pitch; }
double getYaw() const { return yaw; }
friend class UASWaypointManager;
protected:
int uasId; ///< Unique system ID
int type; ///< UAS type (from type enum)
unsigned char type; ///< UAS type (from type enum)
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
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
@ -164,6 +165,7 @@ protected: @@ -164,6 +165,7 @@ protected:
public:
UASWaypointManager &getWaypointManager(void) { return waypointManager; }
int getSystemType();
unsigned char getAutopilotType() {return autopilot;}
public slots:
/** @brief Launches the system **/

3
src/uas/UASInterface.h

@ -157,6 +157,7 @@ public: @@ -157,6 +157,7 @@ public:
return color;
}
virtual unsigned char getAutopilotType() = 0;
public slots:
/** @brief Launches the system/Liftof **/
@ -241,6 +242,8 @@ public slots: @@ -241,6 +242,8 @@ public slots:
virtual void startGyroscopeCalibration() = 0;
virtual void startPressureCalibration() = 0;
protected:
QColor color;

702
src/ui/MainWindow.cc

@ -54,11 +54,11 @@ MainWindow::MainWindow(QWidget *parent) : @@ -54,11 +54,11 @@ MainWindow::MainWindow(QWidget *parent) :
// Setup user interface
ui.setupUi(this);
buildWidgets();
buildCommonWidgets();
connectWidgets();
connectCommonWidgets();
arrangeCenterStack();
arrangeCommonCenterStack();
configureWindowName();
@ -72,9 +72,8 @@ MainWindow::MainWindow(QWidget *parent) : @@ -72,9 +72,8 @@ MainWindow::MainWindow(QWidget *parent) :
// Set style sheet as last step
reloadStylesheet();
// Create actions
connectActions();
connectCommonActions();
// Load widgets and show application windowa
loadWidgets();
@ -90,7 +89,34 @@ MainWindow::~MainWindow() @@ -90,7 +89,34 @@ MainWindow::~MainWindow()
}
void MainWindow::buildWidgets()
void MainWindow::buildCommonWidgets()
{
//TODO: move protocol outside UI
mavlink = new MAVLinkProtocol();
// Center widgets
mapWidget = new MapWidget(this);
protocolWidget = new XMLCommProtocolWidget(this);
// 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) );
debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
debugConsoleDockWidget->setWidget( new DebugConsole(this) );
}
void MainWindow::buildPxWidgets()
{
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList();
@ -106,15 +132,11 @@ void MainWindow::buildWidgets() @@ -106,15 +132,11 @@ void MainWindow::buildWidgets()
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
@ -127,24 +149,9 @@ void MainWindow::buildWidgets() @@ -127,24 +149,9 @@ void MainWindow::buildWidgets()
#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) );
@ -170,6 +177,22 @@ void MainWindow::buildWidgets() @@ -170,6 +177,22 @@ void MainWindow::buildWidgets()
//FIXME: free memory in destructor
joystick = new JoystickInput();
}
void MainWindow::buildSlugsWidgets()
{
// Center widgets
linechartWidget = new Linecharts(this);
hudWidget = new HUD(320, 240, this);
// Dock widgets
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));
// Dialog widgets
slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
@ -183,26 +206,17 @@ void MainWindow::buildWidgets() @@ -183,26 +206,17 @@ void MainWindow::buildWidgets()
slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
}
/**
* Connect all signals and slots of the main window widgets
* Connect the signals and slots of the common window widgets
*/
void MainWindow::connectWidgets()
void MainWindow::connectCommonWidgets()
{
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
@ -219,8 +233,34 @@ void MainWindow::connectWidgets() @@ -219,8 +233,34 @@ void MainWindow::connectWidgets()
//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)));
}
}
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)));
}
if (slugsHilSimWidget && slugsHilSimWidget->widget()){
@ -236,14 +276,28 @@ void MainWindow::connectWidgets() @@ -236,14 +276,28 @@ void MainWindow::connectWidgets()
}
void MainWindow::arrangeCenterStack()
void MainWindow::arrangeCommonCenterStack()
{
QStackedWidget *centerStack = new QStackedWidget(this);
centerStack = new QStackedWidget(this);
if (!centerStack) return;
if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget);
setCentralWidget(centerStack);
}
void MainWindow::arrangePxCenterStack()
{
if (!centerStack) {
qDebug() << "Center Stack not Created!";
return;
}
if (linechartWidget) centerStack->addWidget(linechartWidget);
#ifdef QGC_OSG_ENABLED
if (_3DWidget) centerStack->addWidget(_3DWidget);
#endif
@ -256,7 +310,21 @@ void MainWindow::arrangeCenterStack() @@ -256,7 +310,21 @@ void MainWindow::arrangeCenterStack()
if (hudWidget) centerStack->addWidget(hudWidget);
if (dataplotWidget) centerStack->addWidget(dataplotWidget);
setCentralWidget(centerStack);
}
void MainWindow::arrangeSlugsCenterStack()
{
if (!centerStack) {
qDebug() << "Center Stack not Created!";
return;
}
if (linechartWidget) centerStack->addWidget(linechartWidget);
if (hudWidget) centerStack->addWidget(hudWidget);
}
void MainWindow::configureWindowName()
@ -375,15 +443,71 @@ void MainWindow::showStatusMessage(const QString& status) @@ -375,15 +443,71 @@ void MainWindow::showStatusMessage(const QString& status)
* @brief Create all actions associated to the main window
*
**/
void MainWindow::connectActions()
void MainWindow::buildHelpMenu (){
QIcon icon;
icon = QIcon(":/images/apps/utilities-system-monitor.svg");
actionOnline_documentation = new QAction(icon,tr("Online Documentation"), this);
icon = QIcon(":/images/status/software-update-available.svg");
actionProject_Roadmap = new QAction(icon,tr("Project Roadmap"), this);
icon = QIcon(":/images/categories/preferences-system.svg");
actionCredits_Developers = new QAction(icon,tr("Developer Credits"), this);
helpMenu = ui.menuBar->addMenu(tr("Help"));
helpMenu->addAction(actionOnline_documentation);
helpMenu->addAction(actionProject_Roadmap);
helpMenu->addAction(actionCredits_Developers);
}
void MainWindow::buildViewsMenu (){
QIcon icon;
icon = QIcon(":/images/status/weather-overcast.svg");
actionFlightView = new QAction(icon,"Flight View", this);
icon = QIcon(":/images/apps/utilities-system-monitor.svg");
actionEngineerView = new QAction(icon,"Engineer View", this);
icon = QIcon(":/images/status/network-wireless-encrypted.svg");
actionCalibrationView = new QAction(icon,"Calibration View", this);
icon = QIcon(":/images/devices/network-wired.svg");
actionMavlinkView = new QAction(icon,"Mavlink View", this);
icon = QIcon(":/images/categories/applications-internet.svg");
actionReloadStyle = new QAction(icon,"Reload Style", this);
viewsMenu = ui.menuBar->addMenu("Views");
viewsMenu->addAction(actionFlightView);
viewsMenu->addAction(actionEngineerView);
viewsMenu->addAction(actionCalibrationView);
viewsMenu->addSeparator();
viewsMenu->addAction(actionMavlinkView);
viewsMenu->addAction(actionReloadStyle);
}
void MainWindow::connectCommonActions()
{
buildViewsMenu();
buildHelpMenu();
// 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
// Unmanned System 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()));
@ -391,43 +515,34 @@ void MainWindow::connectActions() @@ -391,43 +515,34 @@ void MainWindow::connectActions()
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
// Views actions
connect(actionFlightView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
connect(actionEngineerView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
connect(actionCalibrationView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
#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
connect(actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
connect(actionReloadStyle, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
// Joystick configuration
connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
// Help Actions
connect(actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
connect(actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
connect(actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
// Slugs View
connect(ui.actionShow_Slugs_View, SIGNAL(triggered()), this, SLOT(loadSlugsView()));
//GlobalOperatorView
// connect(ui.actionGlobalOperatorView,SIGNAL(triggered()),waypointsDockWidget->widget(),SLOT())
}
void MainWindow::connectPxActions()
{
ui.actionJoystickSettings->setVisible(true);
// Joystick configuration
connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
}
void MainWindow::connectSlugsActions()
{
}
@ -582,21 +697,60 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -582,21 +697,60 @@ void MainWindow::UASCreated(UASInterface* uas)
// TODO Stylesheet reloading should in theory not be necessary
reloadStylesheet();
// Check which type this UAS is of
PxQuadMAV* mav = dynamic_cast<PxQuadMAV*>(uas);
if (mav) loadPixhawkView();
if (slugsDataWidget) {
SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
if (dataWidget) {
SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
if (mav2) {
dataWidget->addUAS(uas);
//loadSlugsView();
loadGlobalOperatorView();
}
}
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;
loadEngineerView();
}
}
}
@ -714,7 +868,7 @@ void MainWindow::loadSlugsView() @@ -714,7 +868,7 @@ void MainWindow::loadSlugsView()
this->show();
}
void MainWindow::loadPixhawkView()
void MainWindow::loadPixhawkEngineerView()
{
clearView();
// Engineer view, used in EMAV2009
@ -930,7 +1084,7 @@ void MainWindow::loadOperatorView() @@ -930,7 +1084,7 @@ void MainWindow::loadOperatorView()
this->show();
}
void MainWindow::loadGlobalOperatorView()
void MainWindow::loadSlugsEngineerView()
{
clearView();
@ -959,76 +1113,20 @@ void MainWindow::loadGlobalOperatorView() @@ -959,76 +1113,20 @@ void MainWindow::loadGlobalOperatorView()
slugsDataWidget->show();
}
// Slugs Data View
// Slugs PID Tunning
if (slugsPIDControlWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget);
slugsPIDControlWidget->show();
}
// Slug Camera Control
if (slugsCamControlWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
slugsCamControlWidget->show();
}
// // 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();
// }
// // HORIZONTAL SITUATION INDICATOR
// if (hsiDockWidget)
// {
// HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
// if (hsi)
// {
// addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
// hsiDockWidget->show();
// hsi->start();
// }
// }
// PROCESS CONTROL
// if (watchdogControlDockWidget)
// {
// addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
// watchdogControlDockWidget->show();
// }
// HEAD UP DISPLAY
// if (headUpDockWidget)
// {
// addDockWidget(Qt::RightDockWidgetArea, headUpDockWidget);
// // FIXME Replace with default ->show() call
// HUD* hud = dynamic_cast<HUD*>(headUpDockWidget->widget());
// if (hud)
// {
// headUpDockWidget->show();
// hud->start();
// }
// }
}
void MainWindow::load3DMapView()
@ -1194,64 +1292,16 @@ void MainWindow::loadEngineerView() @@ -1194,64 +1292,16 @@ void MainWindow::loadEngineerView()
clearView();
// Engineer view, used in EMAV2009
// LINE CHART
if (linechartWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
}
}
// UAS CONTROL
if (controlDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST
if (listDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS
if (infoDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// DEBUG CONSOLE
if (debugConsoleDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
debugConsoleDockWidget->show();
}
switch (UASManager::instance()->getActiveUAS()->getAutopilotType()){
case (MAV_AUTOPILOT_GENERIC):
case (MAV_AUTOPILOT_ARDUPILOTMEGA):
case (MAV_AUTOPILOT_PIXHAWK):
loadPixhawkEngineerView();
break;
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
case (MAV_AUTOPILOT_SLUGS):
loadSlugsEngineerView();
break;
}
this->show();
@ -1368,3 +1418,233 @@ void MainWindow::loadWidgets() @@ -1368,3 +1418,233 @@ void MainWindow::loadWidgets()
loadEngineerView();
//loadPilotView();
}
/*
==================================
========== 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())
}
*/

46
src/ui/MainWindow.h

@ -133,9 +133,6 @@ public slots: @@ -133,9 +133,6 @@ public slots:
void loadDataView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/** @brief Load view for global operator, allowing to flight on earth */
void loadGlobalOperatorView();
/** @brief Show the online help for users */
void showHelp();
/** @brief Show the authors / credits */
@ -145,7 +142,9 @@ public slots: @@ -145,7 +142,9 @@ public slots:
// Fixme find a nicer solution that scales to more AP types
void loadSlugsView();
void loadPixhawkView();
void loadPixhawkEngineerView();
void loadSlugsEngineerView();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
@ -153,13 +152,31 @@ protected: @@ -153,13 +152,31 @@ protected:
QStatusBar* statusBar;
QStatusBar* createStatusBar();
void loadWidgets();
void connectActions();
void clearView();
void buildWidgets();
void connectWidgets();
void arrangeCenterStack();
void buildCommonWidgets();
void buildPxWidgets();
void buildSlugsWidgets();
void connectCommonWidgets();
void connectPxWidgets();
void connectSlugsWidgets();
void arrangeCommonCenterStack();
void arrangePxCenterStack();
void arrangeSlugsCenterStack();
void connectCommonActions();
void connectPxActions();
void connectSlugsActions();
void configureWindowName();
void buildHelpMenu ();
void buildViewsMenu ();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
AS4Protocol* as4link;
@ -168,6 +185,8 @@ protected: @@ -168,6 +185,8 @@ protected:
LinkInterface* udpLink;
QSettings settings;
QStackedWidget *centerStack;
// Center widgets
QPointer<Linecharts> linechartWidget;
QPointer<HUD> hudWidget;
@ -215,6 +234,17 @@ protected: @@ -215,6 +234,17 @@ protected:
QAction* stopUASAct;
QAction* killUASAct;
QAction* simulateUASAct;
QAction* actionOnline_documentation;
QAction* actionProject_Roadmap;
QAction* actionCredits_Developers;
QAction* actionCalibrationView;
QAction* actionEngineerView;
QAction* actionFlightView;
QAction* actionMavlinkView;
QAction* actionReloadStyle;
QMenu* helpMenu;
QMenu* viewsMenu;
LogCompressor* comp;
QString screenFileName;

68
src/ui/MainWindow.ui

@ -45,22 +45,11 @@ @@ -45,22 +45,11 @@
<property name="title">
<string>File</string>
</property>
<addaction name="actionJoystickSettings"/>
<addaction name="actionJoystick_Settings"/>
<addaction name="actionSimulate"/>
<addaction name="separator"/>
<addaction name="actionExit"/>
</widget>
<widget class="QMenu" name="menuUnmanned_System">
<property name="title">
<string>Unmanned System</string>
</property>
<addaction name="actionLiftoff"/>
<addaction name="actionLand"/>
<addaction name="actionEmergency_Land"/>
<addaction name="actionEmergency_Kill"/>
<addaction name="separator"/>
<addaction name="actionConfiguration"/>
</widget>
<widget class="QMenu" name="menuNetwork">
<property name="title">
<string>Network</string>
@ -68,43 +57,35 @@ @@ -68,43 +57,35 @@
<addaction name="actionAdd_Link"/>
<addaction name="separator"/>
</widget>
<widget class="QMenu" name="menuWindow">
<widget class="QMenu" name="menuConnected_Systems">
<property name="title">
<string>Window</string>
<string>Select System</string>
</property>
<addaction name="actionEngineerView"/>
<addaction name="actionPilotView"/>
<addaction name="actionOperatorView"/>
<addaction name="action3DMapView"/>
<addaction name="action3DView"/>
<addaction name="actionGoogleEarthView"/>
<addaction name="actionGlobalOperatorView"/>
<addaction name="separator"/>
<addaction name="actionShow_MAVLink_view"/>
<addaction name="actionShow_data_analysis_view"/>
<addaction name="actionShow_full_view"/>
<addaction name="actionStyleConfig"/>
<addaction name="actionShow_Slugs_View"/>
</widget>
<widget class="QMenu" name="menuHelp">
<widget class="QMenu" name="menuUnmanned_System">
<property name="title">
<string>Help</string>
<string>Unmanned System</string>
</property>
<addaction name="actionOnline_documentation"/>
<addaction name="actionProject_Roadmap"/>
<addaction name="actionCredits_Developers"/>
<property name="separatorsCollapsible">
<bool>false</bool>
</property>
<addaction name="actionLiftoff"/>
<addaction name="actionLand"/>
<addaction name="actionEmergency_Land"/>
<addaction name="actionEmergency_Kill"/>
<addaction name="separator"/>
<addaction name="actionConfiguration"/>
</widget>
<widget class="QMenu" name="menuConnected_Systems">
<widget class="QMenu" name="menuTools">
<property name="title">
<string>Select System</string>
<string>Tools</string>
</property>
</widget>
<addaction name="menuMGround"/>
<addaction name="menuNetwork"/>
<addaction name="menuConnected_Systems"/>
<addaction name="menuUnmanned_System"/>
<addaction name="menuWindow"/>
<addaction name="menuHelp"/>
<addaction name="menuTools"/>
</widget>
<widget class="QToolBar" name="mainToolBar">
<attribute name="toolBarArea">
@ -218,6 +199,9 @@ @@ -218,6 +199,9 @@
<property name="text">
<string>Joystick settings</string>
</property>
<property name="visible">
<bool>true</bool>
</property>
</action>
<action name="actionOperatorView">
<property name="icon">
@ -348,6 +332,18 @@ @@ -348,6 +332,18 @@
<string>Show Slugs View</string>
</property>
</action>
<action name="actionJoystick_Settings">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/input-gaming.svg</normaloff>:/images/devices/input-gaming.svg</iconset>
</property>
<property name="text">
<string>Joystick Settings</string>
</property>
<property name="visible">
<bool>false</bool>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>

4
src/ui/QGCRemoteControlView.cc

@ -115,10 +115,10 @@ void QGCRemoteControlView::setUASId(int id) @@ -115,10 +115,10 @@ void QGCRemoteControlView::setUASId(int id)
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}

Loading…
Cancel
Save