Browse Source

Merged experimental and dev;

QGC4.4
lm 15 years ago
parent
commit
6e00bdcc0b
  1. 6
      qgroundcontrol.pro
  2. 3
      src/Core.cc
  3. 3
      src/QGC.h
  4. 15
      src/comm/MAVLinkSimulationLink.cc
  5. 37
      src/comm/SerialLink.cc
  6. 2
      src/input/Freenect.cc
  7. 2
      src/uas/PxQuadMAV.cc
  8. 7
      src/uas/UAS.cc
  9. 13
      src/ui/HUD.cc
  10. 2
      src/ui/HUD.h
  11. 303
      src/ui/MainWindow.cc
  12. 5
      src/ui/MainWindow.h
  13. 11
      src/ui/MainWindow.ui
  14. 6
      src/ui/QGCMainWindowAPConfigurator.cc
  15. 18
      src/ui/QGCMainWindowAPConfigurator.h
  16. 1
      src/ui/SerialConfigurationWindow.cc
  17. 9
      src/ui/XMLCommProtocolWidget.cc
  18. 10
      src/ui/linechart/LinechartWidget.cc
  19. 2
      src/ui/linechart/LinechartWidget.h
  20. 115
      src/ui/map3D/QGCGoogleEarthView.cc
  21. 6
      src/ui/map3D/QGCGoogleEarthView.h
  22. 2
      src/ui/uas/UASControlWidget.cc

6
qgroundcontrol.pro

@ -249,7 +249,8 @@ HEADERS += src/MG.h \ @@ -249,7 +249,8 @@ HEADERS += src/MG.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
@ -359,7 +360,8 @@ SOURCES += src/main.cc \ @@ -359,7 +360,8 @@ SOURCES += src/main.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")

3
src/Core.cc

@ -157,6 +157,9 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv) @@ -157,6 +157,9 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
**/
Core::~Core()
{
//mainWindow->storeSettings();
mainWindow->hide();
mainWindow->deleteLater();
// Delete singletons
delete LinkManager::instance();
delete UASManager::instance();

3
src/QGC.h

@ -14,6 +14,9 @@ namespace QGC @@ -14,6 +14,9 @@ namespace QGC
/** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs();
const QString APPNAME = "QGROUNDCONTROL";
const QString COMPANYNAME = "OPENMAV";
}
#endif // QGC_H

15
src/comm/MAVLinkSimulationLink.cc

@ -559,16 +559,17 @@ void MAVLinkSimulationLink::mainloop() @@ -559,16 +559,17 @@ void MAVLinkSimulationLink::mainloop()
// Send controller states
// uint8_t attControl = 1;
// uint8_t posXYControl = 1;
// uint8_t posZControl = 0;
// uint8_t posYawControl = 1;
// uint8_t gpsLock = 2;
// uint8_t visLock = 3;
//uint8_t posLock = qMax(gpsLock, visLock);
#ifdef MAVLINK_ENABLED_PIXHAWK
uint8_t attControl = 1;
uint8_t posXYControl = 1;
uint8_t posZControl = 0;
uint8_t posYawControl = 1;
uint8_t gpsLock = 2;
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
#endif

37
src/comm/SerialLink.cc

@ -30,9 +30,11 @@ This file is part of the QGROUNDCONTROL project @@ -30,9 +30,11 @@ This file is part of the QGROUNDCONTROL project
#include <QTimer>
#include <QDebug>
#include <QSettings>
#include <QMutexLocker>
#include "SerialLink.h"
#include "LinkManager.h"
#include "QGC.h"
#include <MG.h>
#ifdef _WIN32
#include "windows.h"
@ -54,12 +56,26 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P @@ -54,12 +56,26 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
#endif
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
if (settings.contains("SERIALLINK_COMM_PORT"))
{
this->porthandle = settings.value("SERIALLINK_COMM_PORT").toString();
setBaudRate(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
}
else
{
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
}
// Set the port name
if (porthandle == "")
@ -282,6 +298,15 @@ bool SerialLink::connect() @@ -282,6 +298,15 @@ bool SerialLink::connect()
**/
bool SerialLink::hardwareConnect()
{
// Store settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
settings.setValue("SERIALLINK_COMM_BAUD", this->baudrate);
settings.setValue("SERIALLINK_COMM_PARITY", this->parity);
settings.setValue("SERIALLINK_COMM_STOPBITS", this->stopBits);
settings.setValue("SERIALLINK_COMM_DATABITS", this->dataBits);
settings.sync();
QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected()));
port->open(QIODevice::ReadWrite);

2
src/input/Freenect.cc

@ -341,7 +341,7 @@ Freenect::readConfigFile(void) @@ -341,7 +341,7 @@ Freenect::readConfigFile(void)
settings.value("transform/R33").toDouble(),
settings.value("transform/Tz").toDouble(),
0.0, 0.0, 0.0, 1.0);
transformMatrix = transformMatrix.transposed();
transformMatrix = transformMatrix.inverted();
baseline = settings.value("transform/baseline").toDouble();
disparityOffset = settings.value("transform/disparity_offset").toDouble();

2
src/uas/PxQuadMAV.cc

@ -41,12 +41,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -41,12 +41,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
// mavlink_message_t* msg = &message;
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t* msg = &message;
if (message.sysid == uasId)
{

7
src/uas/UAS.cc

@ -373,9 +373,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -373,9 +373,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
positionLock = true;
// Send to patch antenna
mavlink_message_t msg;
mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
sendMessage(msg);
// FIXME Message re-routing should be implemented differently
//mavlink_message_t msg;
//mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
//sendMessage(msg);
}
break;
case MAVLINK_MSG_ID_GPS_RAW:

13
src/ui/HUD.cc

@ -165,6 +165,19 @@ HUD::~HUD() @@ -165,6 +165,19 @@ HUD::~HUD()
}
void HUD::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
if (isVisible())
{
refreshTimer->start();
}
else
{
refreshTimer->stop();
}
}
void HUD::start()
{
refreshTimer->start();

2
src/ui/HUD.h

@ -123,6 +123,8 @@ protected: @@ -123,6 +123,8 @@ protected:
float refLineWidthToPen(float line);
/** @brief Rotate a polygon around a point clockwise */
void rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin);
/** @brief Override base class show */
virtual void showEvent(QShowEvent* event);
QImage* image; ///< Double buffer image
QImage glImage; ///< The background / camera image

303
src/ui/MainWindow.cc

@ -16,6 +16,7 @@ @@ -16,6 +16,7 @@
#include <QHostInfo>
#include "MG.h"
#include "QGC.h"
#include "MAVLinkSimulationLink.h"
#include "SerialLink.h"
#include "UDPLink.h"
@ -82,6 +83,33 @@ MainWindow::MainWindow(QWidget *parent): @@ -82,6 +83,33 @@ MainWindow::MainWindow(QWidget *parent):
// Adjust the size
adjustSize();
// Load previous widget setup
// FIXME WORK IN PROGRESS
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
QList<QDockWidget *> dockwidgets = qFindChildren<QDockWidget *>(this);
if (dockwidgets.size())
{
settings.beginGroup("mainwindow/dockwidgets");
for (int i = 0; i < dockwidgets.size(); ++i)
{
QDockWidget *dockWidget = dockwidgets.at(i);
if (dockWidget->parentWidget() == this)
{
if (settings.contains(dockWidget->windowTitle()))
{
dockWidget->setVisible(settings.value(dockWidget->windowTitle(), dockWidget->isVisible()).toBool());
}
}
}
settings.endGroup();
}
this->show();
}
MainWindow::~MainWindow()
@ -127,6 +155,110 @@ void MainWindow::buildCommonWidgets() @@ -127,6 +155,110 @@ void MainWindow::buildCommonWidgets()
}
//=======
//void MainWindow::storeSettings()
//{
// QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
// QList<QDockWidget *> dockwidgets = qFindChildren<QDockWidget *>(this);
// if (dockwidgets.size())
// {
// settings.beginGroup("mainwindow/dockwidgets");
// for (int i = 0; i < dockwidgets.size(); ++i)
// {
// QDockWidget *dockWidget = dockwidgets.at(i);
// if (dockWidget->parentWidget() == this)
// {
// settings.setValue(dockWidget->windowTitle(), QVariant(dockWidget->isVisible()));
// }
// }
// settings.endGroup();
// }
// settings.sync();
//}
//QMenu* MainWindow::createCenterWidgetMenu()
//{
// QMenu* menu = NULL;
// QStackedWidget* centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
// if (centerStack)
// {
// if (centerStack->count() > 0)
// {
// menu = new QMenu(this);
// for (int i = 0; i < centerStack->count(); ++i)
// {
// //menu->addAction(centerStack->widget(i)->actions())
// }
// }
// }
// return menu;
//}
//QMenu* MainWindow::createDockWidgetMenu()
//{
// QMenu *menu = 0;
//#ifndef QT_NO_DOCKWIDGET
// QList<QDockWidget *> dockwidgets = qFindChildren<QDockWidget *>(this);
// if (dockwidgets.size())
// {
// menu = new QMenu(this);
// for (int i = 0; i < dockwidgets.size(); ++i)
// {
// QDockWidget *dockWidget = dockwidgets.at(i);
// if (dockWidget->parentWidget() == this)
// {
// menu->addAction(dockwidgets.at(i)->toggleViewAction());
// }
// }
// menu->addSeparator();
// }
//#endif
// return menu;
//}
////QList<QWidget* >* MainWindow::getMainWidgets()
////{
////}
////QMenu* QMainWindow::getDockWidgetMenu()
////{
//// Q_D(QMainWindow);
//// QMenu *menu = 0;
////#ifndef QT_NO_DOCKWIDGET
//// QList<QDockWidget *> dockwidgets = qFindChildren<QDockWidget *>(this);
//// if (dockwidgets.size()) {
//// menu = new QMenu(this);
//// for (int i = 0; i < dockwidgets.size(); ++i) {
//// QDockWidget *dockWidget = dockwidgets.at(i);
//// if (dockWidget->parentWidget() == this
//// && d->layout->contains(dockWidget)) {
//// menu->addAction(dockwidgets.at(i)->toggleViewAction());
//// }
//// }
//// menu->addSeparator();
//// }
////#endif // QT_NO_DOCKWIDGET
////#ifndef QT_NO_TOOLBAR
//// QList<QToolBar *> toolbars = qFindChildren<QToolBar *>(this);
//// if (toolbars.size()) {
//// if (!menu)
//// menu = new QMenu(this);
//// for (int i = 0; i < toolbars.size(); ++i) {
//// QToolBar *toolBar = toolbars.at(i);
//// if (toolBar->parentWidget() == this
//// && d->layout->contains(toolBar)) {
//// menu->addAction(toolbars.at(i)->toggleViewAction());
//// }
//// }
//// }
////#endif
//// Q_UNUSED(d);
//// return menu;
////}
//>>>>>>> master
void MainWindow::buildPxWidgets()
{
//FIXME: memory of acceptList will never be freed again
@ -172,6 +304,7 @@ void MainWindow::buildPxWidgets() @@ -172,6 +304,7 @@ void MainWindow::buildPxWidgets()
#endif
// Dock widgets
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget()), MENU_DETECTION, Qt::RightDockWidgetArea);
@ -189,9 +322,53 @@ void MainWindow::buildPxWidgets() @@ -189,9 +322,53 @@ void MainWindow::buildPxWidgets()
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) );
addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget()), MENU_HSI, Qt::BottomDockWidgetArea);
headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
//=======
// controlDockWidget = new QDockWidget(tr("Control"), this);
// controlDockWidget->setWidget( new UASControlWidget(this) );
// addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
// controlDockWidget->hide();
// infoDockWidget = new QDockWidget(tr("Status Details"), this);
// infoDockWidget->setWidget( new UASInfoWidget(this) );
// addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
// //infoDockWidget->hide();
// listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
// listDockWidget->setWidget( new UASListWidget(this) );
// addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
// listDockWidget->hide();
// waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
// waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
// addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
// waypointsDockWidget->hide();
// detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
// detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
// addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
// detectionDockWidget->hide();
// debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
// debugConsoleDockWidget->setWidget( new DebugConsole(this) );
// addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
// parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
// parametersDockWidget->setWidget( new ParameterInterface(this) );
// addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
// watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
// watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
// addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
// watchdogControlDockWidget->hide();
// hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
// hsiDockWidget->setWidget( new HSIDisplay(this) );
// addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
//>>>>>>> master
headDown1DockWidget = new QDockWidget(tr("System Stats"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
@ -201,6 +378,18 @@ void MainWindow::buildPxWidgets() @@ -201,6 +378,18 @@ void MainWindow::buildPxWidgets()
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
//=======
// addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
// headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
// headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
// addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
// rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
// rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
// addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
// rcViewDockWidget->hide();
//>>>>>>> master
headUpDockWidget = new QDockWidget(tr("HUD"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
@ -233,16 +422,34 @@ void MainWindow::buildSlugsWidgets() @@ -233,16 +422,34 @@ void MainWindow::buildSlugsWidgets()
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
//=======
// this->addDockWidget(Qt::LeftDockWidgetArea, headUpDockWidget);
slugsPIDControlWidget = new QDockWidget(tr("PID Control"), this);
// // SLUGS
// slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
// slugsDataWidget->setWidget( new SlugsDataSensorView(this));
// addDockWidget(Qt::LeftDockWidgetArea, slugsDataWidget);
// slugsDataWidget->hide();
//>>>>>>> master
slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
slugsHilSimWidget->setWidget( new SlugsHilSim(this));
addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
//=======
// addDockWidget(Qt::BottomDockWidgetArea, slugsPIDControlWidget);
// slugsPIDControlWidget->hide();
slugsCamControlWidget = new QDockWidget(tr("Video Camera Control"), this);
// slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
// slugsHilSimWidget->setWidget( new SlugsHilSim(this));
// addDockWidget(Qt::BottomDockWidgetArea, slugsHilSimWidget);
// slugsHilSimWidget->hide();
//>>>>>>> master
slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this);
slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
@ -474,6 +681,13 @@ void MainWindow::updateLocationSettings (Qt::DockWidgetArea location){ @@ -474,6 +681,13 @@ void MainWindow::updateLocationSettings (Qt::DockWidgetArea location){
break;
}
}
//=======
// addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
// slugsCamControlWidget->hide();
// //FIXME: free memory in destructor
// joystick = new JoystickInput();
//>>>>>>> master
}
/**
@ -1006,7 +1220,8 @@ void MainWindow::clearView() @@ -1006,7 +1220,8 @@ void MainWindow::clearView()
if (dockWidget)
{
// Remove dock widget from main window
this->removeDockWidget(dockWidget);
//this->removeDockWidget(dockWidget);
dockWidget->setVisible(false);
// Deletion of dockWidget would also delete all child
// widgets of dockWidget
// Is there a way to unset a widget from QDockWidget?
@ -1048,6 +1263,14 @@ void MainWindow::loadMAVLinkView() @@ -1048,6 +1263,14 @@ void MainWindow::loadMAVLinkView()
currentView = VIEW_MAVLINK;
presentView();
//=======
// // Slugs Data View
// if (slugsHilSimWidget)
// {
// addDockWidget(Qt::LeftDockWidgetArea, slugsHilSimWidget);
// slugsHilSimWidget->show();
// }
//>>>>>>> master
}
void MainWindow::presentView() {
@ -1224,12 +1447,18 @@ void MainWindow::presentView() { @@ -1224,12 +1447,18 @@ void MainWindow::presentView() {
}
void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view){
bool tempVisible;
QWidget* tempWidget = dockWidgets[centralWidget];
//=======
// // ONBOARD PARAMETERS
// if (parametersDockWidget)
// {
// addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
// parametersDockWidget->show();
// }
//}
//>>>>>>> master
tempVisible = settings.value(buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view)).toBool();
qDebug() << buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view) << tempVisible;
@ -1281,6 +1510,24 @@ void MainWindow::loadAllView() @@ -1281,6 +1510,24 @@ void MainWindow::loadAllView()
hdd->start();
}
}
//<<<<<<< HEAD
//=======
//}
//void MainWindow::loadOperatorView()
//{
// clearView();
// // MAP
// if (mapWidget)
// {
// QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
// if (centerStack)
// {
// centerStack->setCurrentWidget(mapWidget);
// }
// }
//>>>>>>> master
// UAS CONTROL
if (controlDockWidget)
@ -1341,8 +1588,6 @@ void MainWindow::loadAllView() @@ -1341,8 +1588,6 @@ void MainWindow::loadAllView()
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
this->show();
}
void MainWindow::loadWidgets()
@ -1430,7 +1675,6 @@ void MainWindow::load3DMapView() @@ -1430,7 +1675,6 @@ void MainWindow::load3DMapView()
}
}
#endif
this->show();
}
void MainWindow::loadGoogleEarthView()
@ -1480,7 +1724,6 @@ void MainWindow::loadGoogleEarthView() @@ -1480,7 +1724,6 @@ void MainWindow::loadGoogleEarthView()
hsiDockWidget->show();
}
}
this->show();
#endif
}
@ -1534,8 +1777,6 @@ void MainWindow::load3DView() @@ -1534,8 +1777,6 @@ void MainWindow::load3DView()
}
}
#endif
this->show();
}
/*
@ -1586,15 +1827,26 @@ void MainWindow::buildCommonWidgets() @@ -1586,15 +1827,26 @@ void MainWindow::buildCommonWidgets()
listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
listDockWidget->setWidget( new UASListWidget(this) );
<<<<<<< HEAD
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) );
=======
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
}
>>>>>>> master
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
<<<<<<< HEAD
debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
debugConsoleDockWidget->setWidget( new DebugConsole(this) );
@ -1635,6 +1887,16 @@ void MainWindow::buildCommonWidgets() @@ -1635,6 +1887,16 @@ void MainWindow::buildCommonWidgets()
slugsCamControlWidget = new QDockWidget(tr("Video Camera Control"), this);
slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
=======
if (protocolWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(protocolWidget);
}
}
>>>>>>> master
}
void MainWindow::connectWidgets()
@ -1686,6 +1948,7 @@ void MainWindow::connectWidgets() @@ -1686,6 +1948,7 @@ void MainWindow::connectWidgets()
}
<<<<<<< HEAD
void MainWindow::arrangeCommonCenterStack()
{
@ -1707,10 +1970,19 @@ void MainWindow::arrangeCommonCenterStack() @@ -1707,10 +1970,19 @@ void MainWindow::arrangeCommonCenterStack()
if (dataplotWidget) centerStack->addWidget(dataplotWidget);
setCentralWidget(centerStack);
=======
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
>>>>>>> master
}
void MainWindow::connectActions()
{
<<<<<<< HEAD
// Connect actions from ui
connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink()));
@ -1763,6 +2035,9 @@ void MainWindow::connectActions() @@ -1763,6 +2035,9 @@ void MainWindow::connectActions()
//GlobalOperatorView
// connect(ui.actionGlobalOperatorView,SIGNAL(triggered()),waypointsDockWidget->widget(),SLOT())
=======
//loadEngineerView();
>>>>>>> master
}
*/

5
src/ui/MainWindow.h

@ -87,6 +87,9 @@ public: @@ -87,6 +87,9 @@ public:
~MainWindow();
public slots:
// /** @brief Store the mainwindow settings */
// void storeSettings();
/**
* @brief Shows a status message on the bottom status bar
*
@ -324,7 +327,6 @@ protected: @@ -324,7 +327,6 @@ protected:
void configureWindowName();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
AS4Protocol* as4link;
@ -367,6 +369,7 @@ protected: @@ -367,6 +369,7 @@ protected:
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> hudDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsPIDControlWidget;
QPointer<QDockWidget> slugsHilSimWidget;

11
src/ui/MainWindow.ui

@ -108,14 +108,7 @@ @@ -108,14 +108,7 @@
<addaction name="menuPerspectives"/>
<addaction name="menuHelp"/>
</widget>
<widget class="QToolBar" name="mainToolBar">
<attribute name="toolBarArea">
<enum>TopToolBarArea</enum>
</attribute>
<attribute name="toolBarBreak">
<bool>false</bool>
</attribute>
</widget>
<widget class="QStatusBar" name="statusBar"/>
<action name="actionExit">
<property name="icon">
@ -461,3 +454,5 @@ @@ -461,3 +454,5 @@
</connection>
</connections>
</ui>

6
src/ui/QGCMainWindowAPConfigurator.cc

@ -0,0 +1,6 @@ @@ -0,0 +1,6 @@
#include "QGCMainWindowAPConfigurator.h"
QGCMainWindowAPConfigurator::QGCMainWindowAPConfigurator(QObject *parent) :
QObject(parent)
{
}

18
src/ui/QGCMainWindowAPConfigurator.h

@ -0,0 +1,18 @@ @@ -0,0 +1,18 @@
#ifndef QGCMAINWINDOWAPCONFIGURATOR_H
#define QGCMAINWINDOWAPCONFIGURATOR_H
#include <QObject>
class QGCMainWindowAPConfigurator : public QObject
{
Q_OBJECT
public:
explicit QGCMainWindowAPConfigurator(QObject *parent = 0);
signals:
public slots:
};
#endif // QGCMAINWINDOWAPCONFIGURATOR_H

1
src/ui/SerialConfigurationWindow.cc

@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project @@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project
#include <SerialConfigurationWindow.h>
#include <SerialLinkInterface.h>
#include <QDir>
#include <QSettings>
#include <QFileInfoList>
#ifdef _WIN32
#include <QextSerialEnumerator.h>

9
src/ui/XMLCommProtocolWidget.cc

@ -7,6 +7,7 @@ @@ -7,6 +7,7 @@
#include "ui_XMLCommProtocolWidget.h"
#include "MAVLinkXMLParser.h"
#include "MAVLinkSyntaxHighlighter.h"
#include "QGC.h"
#include <QDebug>
#include <iostream>
@ -31,7 +32,7 @@ XMLCommProtocolWidget::XMLCommProtocolWidget(QWidget *parent) : @@ -31,7 +32,7 @@ XMLCommProtocolWidget::XMLCommProtocolWidget(QWidget *parent) :
void XMLCommProtocolWidget::selectXMLFile()
{
//QString fileName = QFileDialog::getOpenFileName(this, tr("Load Protocol Definition File"), ".", "*.xml");
QSettings settings;
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
const QString mavlinkXML = "MAVLINK_XML_FILE";
QString dirPath = settings.value(mavlinkXML, QCoreApplication::applicationDirPath() + "../").toString();
QFileDialog dialog;
@ -56,6 +57,7 @@ void XMLCommProtocolWidget::selectXMLFile() @@ -56,6 +57,7 @@ void XMLCommProtocolWidget::selectXMLFile()
setXML(instanceText);
// Store filename for next time
settings.setValue(mavlinkXML, QFileInfo(file).absoluteFilePath());
settings.sync();
}
else
{
@ -92,7 +94,7 @@ void XMLCommProtocolWidget::setXML(const QString& xml) @@ -92,7 +94,7 @@ void XMLCommProtocolWidget::setXML(const QString& xml)
void XMLCommProtocolWidget::selectOutputDirectory()
{
QSettings settings;
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
const QString mavlinkOutputDir = "MAVLINK_OUTPUT_DIR";
QString dirPath = settings.value(mavlinkOutputDir, QCoreApplication::applicationDirPath() + "../").toString();
QFileDialog dialog;
@ -110,7 +112,8 @@ void XMLCommProtocolWidget::selectOutputDirectory() @@ -110,7 +112,8 @@ void XMLCommProtocolWidget::selectOutputDirectory()
{
m_ui->outputDirNameLabel->setText(fileNames.first());
// Store directory for next time
settings.setValue(mavlinkOutputDir, fileNames.first());
settings.setValue(mavlinkOutputDir, QFileInfo(fileNames.first()).absoluteFilePath());
settings.sync();
//QFile file(fileName);
}
}

10
src/ui/linechart/LinechartWidget.cc

@ -159,7 +159,9 @@ void LinechartWidget::createLayout() @@ -159,7 +159,9 @@ void LinechartWidget::createLayout()
QToolButton* timeButton = new QToolButton(this);
timeButton->setText(tr("Ground Time"));
timeButton->setCheckable(true);
timeButton->setChecked(false);
bool gTimeDefault = true;
if (activePlot) activePlot->enforceGroundTime(gTimeDefault);
timeButton->setChecked(gTimeDefault);
layout->addWidget(timeButton, 1, 4);
layout->setColumnStretch(4, 0);
connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool)));
@ -442,6 +444,12 @@ void LinechartWidget::removeCurve(QString curve) @@ -442,6 +444,12 @@ void LinechartWidget::removeCurve(QString curve)
// Remove name
}
void LinechartWidget::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
setActive(isVisible());
}
void LinechartWidget::setActive(bool active)
{
if (activePlot)

2
src/ui/linechart/LinechartWidget.h

@ -77,6 +77,8 @@ public slots: @@ -77,6 +77,8 @@ public slots:
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
void setPlotInterval(quint64 interval);
/** @brief Override base class show */
virtual void showEvent(QShowEvent* event);
void setActive(bool active);
/** @brief Set the number of values to average over */
void setAverageWindow(int windowSize);

115
src/ui/map3D/QGCGoogleEarthView.cc

@ -16,9 +16,11 @@ @@ -16,9 +16,11 @@
QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
QWidget(parent),
updateTimer(new QTimer(this)),
refreshRateMs(200),
mav(NULL),
followCamera(true),
trailEnabled(true),
webViewInitialized(false),
#if (defined Q_OS_MAC)
webViewMac(new QWebView(this)),
#endif
@ -34,22 +36,14 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) : @@ -34,22 +36,14 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
#endif
ui->setupUi(this);
#if (defined Q_OS_MAC)
ui->webViewLayout->addWidget(webViewMac);
webViewMac->setPage(new QGCWebPage(webViewMac));
webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
webViewMac->load(QUrl("earth.html"));
#endif
#if (defined Q_OS_WIN) & !(defined __MINGW32__)
webViewWin->load(QUrl("earth.html"));
#endif
#if ((defined Q_OS_MAC) | ((defined Q_OS_WIN) & !(defined __MINGW32__)))
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState()));
updateTimer->start(200);
updateTimer->start(refreshRateMs);
#endif
// Follow checkbox
@ -94,53 +88,82 @@ void QGCGoogleEarthView::follow(bool follow) @@ -94,53 +88,82 @@ void QGCGoogleEarthView::follow(bool follow)
followCamera = follow;
}
void QGCGoogleEarthView::updateState()
void QGCGoogleEarthView::hide()
{
#ifdef Q_OS_MAC
if (webViewMac->page()->currentFrame()->evaluateJavaScript("isInitialized();").toBool())
updateTimer->stop();
QWidget::hide();
}
void QGCGoogleEarthView::show()
{
if (!webViewInitialized)
{
static bool initialized = false;
if (!initialized)
{
webViewMac->page()->currentFrame()->evaluateJavaScript("setGCSHome(22.679833,8.549444, 470);");
initialized = true;
}
int uasId = 0;
double lat = 22.679833;
double lon = 8.549444;
double alt = 470.0;
#if (defined Q_OS_MAC)
webViewMac->setPage(new QGCWebPage(webViewMac));
webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
webViewMac->load(QUrl("earth.html"));
#endif
float roll = 0.0f;
float pitch = 0.0f;
float yaw = 0.0f;
#if (defined Q_OS_WIN) & !(defined __MINGW32__)
webViewWin->load(QUrl("earth.html"));
#endif
webViewInitialized = true;
}
updateTimer->start();
QWidget::show();
}
if (mav)
{
uasId = mav->getUASID();
lat = mav->getLatitude();
lon = mav->getLongitude();
alt = mav->getAltitude();
roll = mav->getRoll();
pitch = mav->getPitch();
yaw = mav->getYaw();
}
webViewMac->page()->currentFrame()->evaluateJavaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
.arg(uasId)
.arg(lat)
.arg(lon)
.arg(alt+500)
.arg(roll)
.arg(pitch)
.arg(yaw));
if (followCamera)
void QGCGoogleEarthView::updateState()
{
#ifdef Q_OS_MAC
if (isVisible())
{
if (webViewMac->page()->currentFrame()->evaluateJavaScript("isInitialized();").toBool())
{
webViewMac->page()->currentFrame()->evaluateJavaScript(QString("updateFollowAircraft()"));
static bool initialized = false;
if (!initialized)
{
webViewMac->page()->currentFrame()->evaluateJavaScript("setGCSHome(22.679833,8.549444, 470);");
initialized = true;
}
int uasId = 0;
double lat = 22.679833;
double lon = 8.549444;
double alt = 470.0;
float roll = 0.0f;
float pitch = 0.0f;
float yaw = 0.0f;
if (mav)
{
uasId = mav->getUASID();
lat = mav->getLatitude();
lon = mav->getLongitude();
alt = mav->getAltitude();
roll = mav->getRoll();
pitch = mav->getPitch();
yaw = mav->getYaw();
}
webViewMac->page()->currentFrame()->evaluateJavaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
.arg(uasId)
.arg(lat)
.arg(lon)
.arg(alt+500)
.arg(roll)
.arg(pitch)
.arg(yaw));
if (followCamera)
{
webViewMac->page()->currentFrame()->evaluateJavaScript(QString("updateFollowAircraft()"));
}
}
}
#endif
}
void QGCGoogleEarthView::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);

6
src/ui/map3D/QGCGoogleEarthView.h

@ -62,13 +62,19 @@ public slots: @@ -62,13 +62,19 @@ public slots:
void showWaypoints(bool state);
/** @brief Follow the aircraft during flight */
void follow(bool follow);
/** @brief Hide and deactivate */
void hide();
/** @brief Show and activate */
void show();
protected:
void changeEvent(QEvent *e);
QTimer* updateTimer;
int refreshRateMs;
UASInterface* mav;
bool followCamera;
bool trailEnabled;
bool webViewInitialized;
#if (defined Q_OS_WIN) && !(defined __MINGW32__)
WebAxWidget* webViewWin;
#endif

2
src/ui/uas/UASControlWidget.cc

@ -50,7 +50,7 @@ This file is part of the PIXHAWK project @@ -50,7 +50,7 @@ This file is part of the PIXHAWK project
#define CONTROL_MODE_TEST2 "MODE TEST2"
#define CONTROL_MODE_TEST3 "MODE TEST3"
#define CONTROL_MODE_READY "MODE TEST3"
#define CONTROL_MODE_RC_TRAINING "MODE RC TRAINING"
#define CONTROL_MODE_RC_TRAINING "RC SIMULATION"
#define CONTROL_MODE_LOCKED_INDEX 1
#define CONTROL_MODE_MANUAL_INDEX 2

Loading…
Cancel
Save