diff --git a/files/ardupilotmega/fixed_wing/widgets/ardupilot-heading-pid.qgw b/files/ardupilotmega/fixed_wing/widgets/ardupilot-heading-pid.qgw deleted file mode 100644 index 20a6d1c1f4d3577486afcd03fafb266baa9b6512..0000000000000000000000000000000000000000 --- a/files/ardupilotmega/fixed_wing/widgets/ardupilot-heading-pid.qgw +++ /dev/null @@ -1,26 +0,0 @@ -[Heading%20PID%20Tuning] -QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER -QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Heading D Gain -QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_D -QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=200 -QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1 -QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER -QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Heading P Gain -QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_P -QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=200 -QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=5 -QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER -QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Heading I Gain -QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_I -QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=200 -QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1 -QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER -QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Heading I Limit -QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_IMAX -QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=200 -QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=3000 -QGC_TOOL_WIDGET_ITEMS\size=4 diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index d52beb03bcd04e60d13545188088e24d9311fde5..04f6916439d0701e79fb6a8cdf464f7c598d514b 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -226,7 +226,8 @@ FORMS += src/ui/MainWindow.ui \ src/ui/QGCHilJSBSimConfiguration.ui \ src/ui/QGCHilXPlaneConfiguration.ui \ src/ui/designer/QGCComboBox.ui \ - src/ui/designer/QGCTextLabel.ui + src/ui/designer/QGCTextLabel.ui \ + src/ui/uas/UASQuickView.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -372,7 +373,10 @@ HEADERS += src/MG.h \ src/ui/QGCHilXPlaneConfiguration.h \ src/ui/designer/QGCComboBox.h \ src/ui/designer/QGCTextLabel.h \ - src/ui/submainwindow.h + src/ui/submainwindow.h \ + src/ui/dockwidgettitlebareventfilter.h \ + src/ui/uas/UASQuickView.h \ + src/ui/uas/UASQuickViewItem.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h @@ -537,7 +541,10 @@ SOURCES += src/main.cc \ src/ui/QGCHilXPlaneConfiguration.cc \ src/ui/designer/QGCComboBox.cc \ src/ui/designer/QGCTextLabel.cc \ - src/ui/submainwindow.cpp + src/ui/submainwindow.cpp \ + src/ui/dockwidgettitlebareventfilter.cpp \ + src/ui/uas/UASQuickViewItem.cc \ + src/ui/uas/UASQuickView.cc # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/configuration.h b/src/configuration.h index 21ee4e375a151cb9decf3a76e41d70f91b627f76..a4d4cc93a234987362a5197c4c01a4d9bb1032d7 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -11,14 +11,14 @@ #define WITH_TEXT_TO_SPEECH 1 #define QGC_APPLICATION_NAME "QGroundControl" -#define QGC_APPLICATION_VERSION "v. 1.0.7 (beta)" +#define QGC_APPLICATION_VERSION "v. 1.0.8 (beta)" namespace QGC { const QString APPNAME = "QGROUNDCONTROL"; const QString COMPANYNAME = "QGROUNDCONTROL"; -const int APPLICATIONVERSION = 107; // 1.0.7 +const int APPLICATIONVERSION = 108; // 1.0.8 } #endif // QGC_CONFIGURATION_H diff --git a/src/main.cc b/src/main.cc index 910c57e6bc2da580107bcba2197654989a3c815f..d09dc6c20f777b49410fd678bb7a5ed6f947d22d 100644 --- a/src/main.cc +++ b/src/main.cc @@ -64,7 +64,6 @@ void msgHandler( QtMsgType type, const char* msg ) int main(int argc, char *argv[]) { - // install the message handler #ifdef Q_OS_WIN qInstallMsgHandler( msgHandler ); diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index c56992bc9795ae7872fa1f0f439cb2af116306b3..06eddf9bb2f542b85afbcf6e6c580c45358278a5 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -77,16 +77,10 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), localX(0.0), localY(0.0), localZ(0.0), - latitude(0.0), - longitude(0.0), - altitude(0.0), globalEstimatorActive(false), latitude_gps(0.0), longitude_gps(0.0), altitude_gps(0.0), - roll(0.0), - pitch(0.0), - yaw(0.0), statusTimeout(new QTimer(this)), #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) receivedOverlayTimestamp(0.0), @@ -624,9 +618,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) if (!wrongComponent) { lastAttitude = time; - roll = QGC::limitAngleToPMPIf(attitude.roll); - pitch = QGC::limitAngleToPMPIf(attitude.pitch); - yaw = QGC::limitAngleToPMPIf(attitude.yaw); + //roll = QGC::limitAngleToPMPIf(attitude.roll); + setRoll(QGC::limitAngleToPMPIf(attitude.roll)); + //pitch = QGC::limitAngleToPMPIf(attitude.pitch); + setPitch(QGC::limitAngleToPMPIf(attitude.pitch)); + //yaw = QGC::limitAngleToPMPIf(attitude.yaw); + setYaw(QGC::limitAngleToPMPIf(attitude.yaw)); // // Emit in angles @@ -646,7 +643,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // } attitudeKnown = true; - emit attitudeChanged(this, roll, pitch, yaw, time); + emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time); emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); } } @@ -680,8 +677,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) if (!attitudeKnown) { - yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI); - emit attitudeChanged(this, roll, pitch, yaw, time); + //yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI); + setYaw(QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI)); + emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time); } emit altitudeChanged(uasId, hud.alt); @@ -737,14 +735,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_global_position_int_t pos; mavlink_msg_global_position_int_decode(&message, &pos); quint64 time = getUnixTime(); - latitude = pos.lat/(double)1E7; - longitude = pos.lon/(double)1E7; - altitude = pos.alt/1000.0; + //latitude = pos.lat/(double)1E7; + setLatitude(pos.lat/(double)1E7); + //longitude = pos.lon/(double)1E7; + setLongitude(pos.lon/(double)1E7); + //altitude = pos.alt/1000.0; + setAltitude(pos.alt/1000.0); globalEstimatorActive = true; speedX = pos.vx/100.0; speedY = pos.vy/100.0; speedZ = pos.vz/100.0; - emit globalPositionChanged(this, latitude, longitude, altitude, time); + emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time); emit speedChanged(this, speedX, speedY, speedZ, time); // Set internal state @@ -777,18 +778,23 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) loc_type = 0; } emit localizationChanged(this, loc_type); + setSatelliteCount(pos.satellites_visible); if (pos.fix_type > 2) { + latitude_gps = pos.lat/(double)1E7; longitude_gps = pos.lon/(double)1E7; altitude_gps = pos.alt/1000.0; if (!globalEstimatorActive) { - latitude = latitude_gps; - longitude = longitude_gps; - altitude = altitude_gps; - emit globalPositionChanged(this, latitude, longitude, altitude, time); + //latitude = latitude_gps; + setLatitude(latitude_gps); + //longitude = longitude_gps; + setLongitude(longitude_gps); + //altitude = altitude_gps; + setAltitude(altitude_gps); + emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time); } positionLock = true; @@ -819,6 +825,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) { emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast(pos.satellite_used[i])); } + setSatelliteCount(pos.satellites_visible); } break; case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: @@ -1337,6 +1344,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) case MAVLINK_MSG_ID_RAW_IMU: case MAVLINK_MSG_ID_SCALED_IMU: case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: + { + //mavlink_set_local_position_setpoint_t p; + //mavlink_msg_set_local_position_setpoint_decode(&message, &p); + //emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw); + mavlink_nav_controller_output_t p; + mavlink_msg_nav_controller_output_decode(&message,&p); + setDistToWaypoint(p.wp_dist); + } + break; case MAVLINK_MSG_ID_RAW_PRESSURE: case MAVLINK_MSG_ID_SCALED_PRESSURE: case MAVLINK_MSG_ID_OPTICAL_FLOW: diff --git a/src/uas/UAS.h b/src/uas/UAS.h index bfb02bf7039c770a1fe71c6dd3e03cc35f7700fe..dabce4b1b7c3208932d8e5c3fb53cf8ff1c8f1e9 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -100,30 +100,99 @@ public: /** @brief Get the links associated with this robot */ QList* getLinks(); + Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged) + Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged) + Q_PROPERTY(double localZ READ getLocalZ WRITE setLocalZ NOTIFY localZChanged) + Q_PROPERTY(double latitude READ getLatitude WRITE setLatitude NOTIFY latitudeChanged) + Q_PROPERTY(double longitude READ getLongitude WRITE setLongitude NOTIFY longitudeChanged) + Q_PROPERTY(double altitude READ getAltitude WRITE setAltitude NOTIFY altitudeChanged) + Q_PROPERTY(double satelliteCount READ getSatelliteCount WRITE setSatelliteCount NOTIFY satelliteCountChanged) + Q_PROPERTY(bool isLocalPositionKnown READ localPositionKnown) + Q_PROPERTY(bool isGlobalPositionKnown READ globalPositionKnown) + Q_PROPERTY(double roll READ getRoll WRITE setRoll NOTIFY rollChanged) + Q_PROPERTY(double pitch READ getPitch WRITE setPitch NOTIFY pitchChanged) + Q_PROPERTY(double yaw READ getYaw WRITE setYaw NOTIFY yawChanged) + Q_PROPERTY(double distToWaypoint READ getDistToWaypoint WRITE setDistToWaypoint NOTIFY distToWaypointChanged) + + void setLocalX(double val) + { + localX = val; + emit localXChanged(val,"localX"); + emit valueChanged(this->uasId,"localX","M",QVariant(val),getUnixTime()); + } double getLocalX() const { return localX; } + + void setLocalY(double val) + { + localY = val; + emit localYChanged(val,"localY"); + emit valueChanged(this->uasId,"localY","M",QVariant(val),getUnixTime()); + } double getLocalY() const { return localY; } + + void setLocalZ(double val) + { + localZ = val; + emit localZChanged(val,"localZ"); + emit valueChanged(this->uasId,"localZ","M",QVariant(val),getUnixTime()); + } double getLocalZ() const { return localZ; } + + void setLatitude(double val) + { + latitude = val; + emit latitudeChanged(val,"latitude"); + emit valueChanged(this->uasId,"latitude","deg",QVariant(val),getUnixTime()); + } double getLatitude() const { return latitude; } + + void setLongitude(double val) + { + longitude = val; + emit longitudeChanged(val,"longitude"); + emit valueChanged(this->uasId,"longitude","deg",QVariant(val),getUnixTime()); + } double getLongitude() const { return longitude; } + + void setAltitude(double val) + { + altitude = val; + emit altitudeChanged(val,"altitude"); + emit valueChanged(this->uasId,"altitude","M",QVariant(val),getUnixTime()); + } + double getAltitude() const { return altitude; } + + void setSatelliteCount(double val) + { + satelliteCount = val; + emit satelliteCountChanged(val,"satelliteCount"); + emit valueChanged(this->uasId,"satelliteCount","M",QVariant(val),getUnixTime()); + } + + double getSatelliteCount() const + { + return satelliteCount; + } + virtual bool localPositionKnown() const { return isLocalPositionKnown; @@ -133,14 +202,46 @@ public: return isGlobalPositionKnown; } + void setDistToWaypoint(double val) + { + distToWaypoint = val; + emit distToWaypointChanged(val,"distToWaypoint"); + emit valueChanged(this->uasId,"distToWaypoint","M",QVariant(val),getUnixTime()); + } + + double getDistToWaypoint() const + { + return distToWaypoint; + } + + void setRoll(double val) + { + roll = val; + emit rollChanged(val,"roll"); + } + double getRoll() const { return roll; } + + void setPitch(double val) + { + pitch = val; + emit pitchChanged(val,"pitch"); + } + double getPitch() const { return pitch; } + + void setYaw(double val) + { + yaw = val; + emit yawChanged(val,"yaw"); + } + double getYaw() const { return yaw; @@ -281,6 +382,7 @@ protected: //COMMENTS FOR TEST UNIT double latitude; ///< Global latitude as estimated by position estimator double longitude; ///< Global longitude as estimated by position estimator double altitude; ///< Global altitude as estimated by position estimator + double satelliteCount; ///< Number of satellites visible to raw GPS bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position double latitude_gps; ///< Global latitude as estimated by raw GPS double longitude_gps; ///< Global longitude as estimated by raw GPS @@ -288,6 +390,7 @@ protected: //COMMENTS FOR TEST UNIT double speedX; ///< True speed in X axis double speedY; ///< True speed in Y axis double speedZ; ///< True speed in Z axis + double distToWaypoint; ///< Distance to next waypoint double roll; double pitch; double yaw; @@ -699,6 +802,21 @@ signals: /** @brief HIL actuator outputs have changed */ void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8); + void localXChanged(double val,QString name); + void localYChanged(double val,QString name); + void localZChanged(double val,QString name); + void longitudeChanged(double val,QString name); + void latitudeChanged(double val,QString name); + void altitudeChanged(double val,QString name); + void altitudeChanged(int uasid, double altitude); + void rollChanged(double val,QString name); + void pitchChanged(double val,QString name); + void yawChanged(double val,QString name); + void satelliteCountChanged(double val,QString name); + void distToWaypointChanged(double val,QString name); + + + protected: /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ quint64 getUnixTime(quint64 time=0); diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 8105060fcd8eed3b2b79bee5097f9362b12e84a9..b06dfedc555670d0ec37d46c3d137e41a78fb7bb 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -449,6 +449,7 @@ signals: void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec); + void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs); void voltageChanged(int uasId, double voltage); void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active); diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc index 1fbc5f3760891143bc95cdb747fd282a68e2b6bc..00bb81ba261c39ba2c9c27ee302d1cbf3e3d595d 100644 --- a/src/uas/UASManager.cc +++ b/src/uas/UASManager.cc @@ -235,7 +235,8 @@ UASManager::UASManager() : homeLat(47.3769), homeLon(8.549444), homeAlt(470.0), - homeFrame(MAV_FRAME_GLOBAL) + homeFrame(MAV_FRAME_GLOBAL), + offlineUASWaypointManager(NULL) { loadSettings(); setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1); @@ -280,6 +281,22 @@ void UASManager::addUAS(UASInterface* uas) if (firstUAS) { setActiveUAS(uas); + if (offlineUASWaypointManager->getWaypointEditableList().size() > 0) + { + if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes) + { + //Need to transfer all waypoints from the offline mode WPManager to the online mode. + for (int i=0;igetWaypointEditableList().size();i++) + { + Waypoint *wp = uas->getWaypointManager()->createWaypoint(); + wp->setLatitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLatitude()); + wp->setLongitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLongitude()); + wp->setAltitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getAltitude()); + } + } + offlineUASWaypointManager->deleteLater(); + offlineUASWaypointManager = 0; + } } } @@ -336,6 +353,20 @@ UASInterface* UASManager::silentGetActiveUAS() { return activeUAS; ///< Return zero pointer if no UAS has been loaded } +UASWaypointManager *UASManager::getActiveUASWaypointManager() +{ + if (activeUAS) + { + return activeUAS->getWaypointManager(); + } + if (!offlineUASWaypointManager) + { + offlineUASWaypointManager = new UASWaypointManager(NULL); + } + return offlineUASWaypointManager; + + +} bool UASManager::launchActiveUAS() { diff --git a/src/uas/UASManager.h b/src/uas/UASManager.h index 6dde682b658d0db525ec627709c334accc30cbb3..ff4c89731f1f5c55fd5f2f0a71d1ec37ec399223 100644 --- a/src/uas/UASManager.h +++ b/src/uas/UASManager.h @@ -58,6 +58,12 @@ public: * @return NULL pointer if no UAS exists, active UAS else **/ UASInterface* getActiveUAS(); + /** + * @brief getActiveUASWaypointManager + * @return uas->getUASWaypointManager(), or if not connected, a singleton instance of a UASWaypointManager. + */ + UASWaypointManager *getActiveUASWaypointManager(); + UASInterface* silentGetActiveUAS(); /** * @brief Get the UAS with this id @@ -244,6 +250,7 @@ protected: UASManager(); QList systems; UASInterface* activeUAS; + UASWaypointManager *offlineUASWaypointManager; QMutex activeUASMutex; double homeLat; double homeLon; diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 4bf3b4456b685cb24350fa51679497da51ddeb5d..d5b8256df2edaec33246a6cc4162f0beb9ed2532 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -2,7 +2,7 @@ QGroundControl Open Source Ground Control Station -(c) 2009 - 2011 QGROUNDCONTROL PROJECT +(c) 2009 - 2013 QGROUNDCONTROL PROJECT This file is part of the QGROUNDCONTROL project @@ -38,7 +38,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include - +#include "dockwidgettitlebareventfilter.h" #include "QGC.h" #include "MAVLinkSimulationLink.h" #include "SerialLink.h" @@ -58,6 +58,7 @@ This file is part of the QGROUNDCONTROL project #include "QGCRGBDView.h" #include "QGCFirmwareUpdate.h" #include "QGCStatusBar.h" +#include "UASQuickView.h" #ifdef QGC_OSG_ENABLED #include "Q3DWidgetFactory.h" @@ -94,7 +95,7 @@ MainWindow* MainWindow::instance(QSplashScreen* screen) **/ MainWindow::MainWindow(QWidget *parent): QMainWindow(parent), - currentView(VIEW_MISSION), + currentView(VIEW_FLIGHT), currentStyle(QGC_MAINWINDOW_STYLE_INDOOR), aboutToCloseFlag(false), changingViewsFlag(false), @@ -104,7 +105,7 @@ MainWindow::MainWindow(QWidget *parent): lowPowerMode(false) { hide(); - + dockWidgetTitleBarEnabled = true; isAdvancedMode = false; emit initStatusChanged("Loading UI Settings.."); loadSettings(); @@ -166,8 +167,8 @@ MainWindow::MainWindow(QWidget *parent): // Add actions for average users (displayed next to each other) QList actions; - actions << ui.actionMissionView; actions << ui.actionFlightView; + actions << ui.actionMissionView; actions << ui.actionConfiguration_2; toolBar->setPerspectiveChangeActions(actions); @@ -364,7 +365,10 @@ void MainWindow::buildCustomWidget() QDockWidget* dock = dynamic_cast(tool->parentWidget()); if (!dock) { - QDockWidget* dock = new QDockWidget(tool->windowTitle(), this); + QSettings settings; + settings.beginGroup("QGC_MAINWINDOW"); + + /*QDockWidget* dock = new QDockWidget(tool->windowTitle(), this); dock->setObjectName(tool->objectName()+"_DOCK"); dock->setWidget(tool); connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); @@ -373,13 +377,36 @@ void MainWindow::buildCustomWidget() connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); widgets.at(i)->setMainMenuAction(showAction); - ui.menuTools->addAction(showAction); + ui.menuTools->addAction(showAction);*/ // Load dock widget location (default is bottom) Qt::DockWidgetArea location = static_cast (tool->getDockWidgetArea(currentView)); - addDockWidget(location, dock); - dock->hide(); + //addDockWidget(location, dock); + //dock->hide(); + int view = settings.value(QString("TOOL_PARENT_") + tool->objectName(),-1).toInt(); + //settings.setValue(QString("TOOL_PARENT_") + "UNNAMED_TOOL_" + QString::number(ui.menuTools->actions().size()),currentView); + settings.endGroup(); + switch (view) + { + case VIEW_ENGINEER: + createDockWidget(dataView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location); + break; + case VIEW_FLIGHT: + createDockWidget(pilotView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location); + break; + case VIEW_SIMULATION: + createDockWidget(simView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location); + break; + case VIEW_MISSION: + createDockWidget(plannerView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location); + break; + default: + createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location); + break; + } + + //createDockWidget(0,tool,tool->getTitle(),tool->objectName(),view,location); } } } @@ -410,7 +437,8 @@ void MainWindow::buildCommonWidgets() { pilotView = new SubMainWindow(this); pilotView->setObjectName("VIEW_FLIGHT"); - pilotView->setCentralWidget(new HUD(320,240,this)); + //pilotView->setCentralWidget(new HUD(320,240,this)); + pilotView->setCentralWidget(new QGCMapTool(this)); //hudWidget = new HUD(320, 240, this); //addCentralWidget(hudWidget, tr("Head Up Display")); //mapWidget = new QGCMapTool(this); @@ -453,9 +481,17 @@ void MainWindow::buildCommonWidgets() connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); createDockWidget(simView,new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",VIEW_SIMULATION,Qt::LeftDockWidgetArea); - createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + createDockWidget(plannerView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_MISSION,Qt::LeftDockWidgetArea); - createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea); + + { + //createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea); + QAction* tempAction = ui.menuTools->addAction(tr("Mission Plan")); + tempAction->setCheckable(true); + connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); + menuToDockNameMap[tempAction] = "WAYPOINT_LIST_DOCKWIDGET"; + } + createDockWidget(simView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea); createDockWidget(engineeringView,new QGCMAVLinkInspector(mavlink,this),tr("MAVLink Inspector"),"MAVLINK_INSPECTOR_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea); @@ -475,8 +511,6 @@ void MainWindow::buildCommonWidgets() tempAction->setCheckable(true); connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); } - - createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::BottomDockWidgetArea); createDockWidget(simView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea); @@ -492,21 +526,44 @@ void MainWindow::buildCommonWidgets() acceptList2->append("0,RAW_PRESSURE.pres_abs,hPa,65500"); - HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this); - hdDisplay->addSource(mavlinkDecoder); - createDockWidget(pilotView,hdDisplay,tr("Flight Display"),"HEAD_DOWN_DISPLAY_1_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); + //HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this); + //hdDisplay->addSource(mavlinkDecoder); + //createDockWidget(pilotView,hdDisplay,tr("Flight Display"),"HEAD_DOWN_DISPLAY_1_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); + + //HDDisplay* hdDisplay2 = new HDDisplay(acceptList2, "Actuator Status", this); + //hdDisplay2->addSource(mavlinkDecoder); + //createDockWidget(pilotView,hdDisplay2,tr("Actuator Status"),"HEAD_DOWN_DISPLAY_2_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); - HDDisplay* hdDisplay2 = new HDDisplay(acceptList2, "Actuator Status", this); - hdDisplay2->addSource(mavlinkDecoder); - createDockWidget(pilotView,hdDisplay2,tr("Actuator Status"),"HEAD_DOWN_DISPLAY_2_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); + { + QAction* tempAction = ui.menuTools->addAction(tr("Flight Display")); + tempAction->setCheckable(true); + connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); + menuToDockNameMap[tempAction] = "HEAD_DOWN_DISPLAY_1_DOCKWIDGET"; + } + + { + QAction* tempAction = ui.menuTools->addAction(tr("Actuator Status")); + tempAction->setCheckable(true); + connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); + menuToDockNameMap[tempAction] = "HEAD_DOWN_DISPLAY_2_DOCKWIDGET"; + } { QAction* tempAction = ui.menuTools->addAction(tr("Radio Control")); tempAction->setCheckable(true); connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); } + + createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5); + createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); + createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8); + createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North); + pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]); + // Custom widgets, added last to all menus and layouts buildCustomWidget(); @@ -608,17 +665,36 @@ void MainWindow::addTool(SubMainWindow *parent,VIEW_SECTIONS view,QDockWidget* w void MainWindow::createDockWidget(QWidget *parent,QWidget *child,QString title,QString objectname,VIEW_SECTIONS view,Qt::DockWidgetArea area,int minwidth,int minheight) { + //if (child->objectName() == "") + //{ + child->setObjectName(objectname); + //} QDockWidget *widget = new QDockWidget(title,this); if (!isAdvancedMode) { - dockToTitleBarMap[widget] = widget->titleBarWidget(); - widget->setTitleBarWidget(new QWidget(this)); + if (dockWidgetTitleBarEnabled) + { + dockToTitleBarMap[widget] = widget->titleBarWidget(); + QLabel *label = new QLabel(this); + label->setText(title); + widget->setTitleBarWidget(label); + label->installEventFilter(new DockWidgetTitleBarEventFilter()); + } + else + { + dockToTitleBarMap[widget] = widget->titleBarWidget(); + widget->setTitleBarWidget(new QWidget(this)); + } } else { - dockToTitleBarMap[widget] = new QWidget(this); + QLabel *label = new QLabel(this); + label->setText(title); + dockToTitleBarMap[widget] = label; + label->installEventFilter(new DockWidgetTitleBarEventFilter()); + label->hide(); } - widget->setObjectName(objectname); + widget->setObjectName(child->objectName()); widget->setWidget(child); if (minheight != 0 || minwidth != 0) { @@ -694,6 +770,10 @@ void MainWindow::loadDockWidget(QString name) { createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); } + else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET") + { + createDockWidget(centerStack->currentWidget(),new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",currentView,Qt::LeftDockWidgetArea); + } else { qDebug() << "Error loading window:" << name; @@ -815,26 +895,35 @@ void MainWindow::connectCommonWidgets() void MainWindow::createCustomWidget() { - QDockWidget* dock = new QDockWidget("Unnamed Tool", this); - QGCToolWidget* tool = new QGCToolWidget("Unnamed Tool", dock); + //void MainWindow::createDockWidget(QWidget *parent,QWidget *child,QString title,QString objectname,VIEW_SECTIONS view,Qt::DockWidgetArea area,int minwidth,int minheight) + //QDockWidget* dock = new QDockWidget("Unnamed Tool", this); if (QGCToolWidget::instances()->size() < 2) { // This is the first widget ui.menuTools->addSeparator(); } + QGCToolWidget* tool = new QGCToolWidget("Unnamed Tool " + QString::number(ui.menuTools->actions().size())); + createDockWidget(centerStack->currentWidget(),tool,"Unnamed Tool " + QString::number(ui.menuTools->actions().size()),"UNNAMED_TOOL_" + QString::number(ui.menuTools->actions().size())+"DOCK",currentView,Qt::BottomDockWidgetArea); + //tool->setObjectName("UNNAMED_TOOL_" + QString::number(ui.menuTools->actions().size())); + QSettings settings; + settings.beginGroup("QGC_MAINWINDOW"); + settings.setValue(QString("TOOL_PARENT_") + tool->objectName(),currentView); + settings.endGroup(); + + - connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); - dock->setWidget(tool); + //connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); + //dock->setWidget(tool); - QAction* showAction = new QAction(tool->getTitle(), this); - showAction->setCheckable(true); - connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); - connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); - tool->setMainMenuAction(showAction); - ui.menuTools->addAction(showAction); - this->addDockWidget(Qt::BottomDockWidgetArea, dock); - dock->setVisible(true); + //QAction* showAction = new QAction(tool->getTitle(), this); + //showAction->setCheckable(true); + //connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); + //connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); + //tool->setMainMenuAction(showAction); + //ui.menuTools->addAction(showAction); + //this->addDockWidget(Qt::BottomDockWidgetArea, dock); + //dock->setVisible(true); } void MainWindow::loadCustomWidget() @@ -849,8 +938,35 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) QGCToolWidget* tool = new QGCToolWidget("", this); if (tool->loadSettings(fileName, true) || !singleinstance) { + qDebug() << "Loading custom tool:" << tool->getTitle() << tool->objectName(); + QSettings settings; + settings.beginGroup("QGC_MAINWINDOW"); + //settings.setValue(QString("TOOL_PARENT_") + "UNNAMED_TOOL_" + QString::number(ui.menuTools->actions().size()),currentView); + + int view = settings.value(QString("TOOL_PARENT_") + tool->objectName(),-1).toInt(); + switch (view) + { + case VIEW_ENGINEER: + createDockWidget(dataView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea); + break; + case VIEW_FLIGHT: + createDockWidget(pilotView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea); + break; + case VIEW_SIMULATION: + createDockWidget(simView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea); + break; + case VIEW_MISSION: + createDockWidget(plannerView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea); + break; + default: + createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea); + break; + } + + + settings.endGroup(); // Add widget to UI - QDockWidget* dock = new QDockWidget(tool->getTitle(), this); + /*QDockWidget* dock = new QDockWidget(tool->getTitle(), this); connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); dock->setWidget(tool); tool->setParent(dock); @@ -862,7 +978,7 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) tool->setMainMenuAction(showAction); ui.menuTools->addAction(showAction); this->addDockWidget(Qt::BottomDockWidgetArea, dock); - dock->hide(); + dock->hide();*/ } else { @@ -908,7 +1024,9 @@ void MainWindow::loadSettings() autoReconnect = settings.value("AUTO_RECONNECT", autoReconnect).toBool(); currentStyle = (QGC_MAINWINDOW_STYLE)settings.value("CURRENT_STYLE", currentStyle).toInt(); lowPowerMode = settings.value("LOW_POWER_MODE", lowPowerMode).toBool(); + dockWidgetTitleBarEnabled = settings.value("DOCK_WIDGET_TITLEBARS",dockWidgetTitleBarEnabled).toBool(); settings.endGroup(); + enableDockWidgetTitleBars(dockWidgetTitleBarEnabled); } void MainWindow::storeSettings() @@ -995,6 +1113,36 @@ void MainWindow::saveScreen() window.save(screenFileName, format.toAscii()); } } +void MainWindow::enableDockWidgetTitleBars(bool enabled) +{ + dockWidgetTitleBarEnabled = enabled; + QSettings settings; + settings.beginGroup("QGC_MAINWINDOW"); + settings.setValue("DOCK_WIDGET_TITLEBARS",dockWidgetTitleBarEnabled); + settings.endGroup(); + settings.sync(); + if (!isAdvancedMode) + { + if (enabled) + { + for (QMap::const_iterator i=dockToTitleBarMap.constBegin();i!=dockToTitleBarMap.constEnd();i++) + { + QLabel *label = new QLabel(this); + label->setText(i.key()->windowTitle()); + i.key()->setTitleBarWidget(label); + //label->setEnabled(false); + label->installEventFilter(new DockWidgetTitleBarEventFilter()); + } + } + else + { + for (QMap::const_iterator i=dockToTitleBarMap.constBegin();i!=dockToTitleBarMap.constEnd();i++) + { + i.key()->setTitleBarWidget(new QWidget(this)); + } + } + } +} void MainWindow::enableAutoReconnect(bool enabled) { @@ -1509,14 +1657,32 @@ void MainWindow::UASCreated(UASInterface* uas) // HIL showHILConfigurationWidget(uas); - // Line chart - /*if (!linechartWidget) + if (!linechartWidget) { - // Center widgets linechartWidget = new Linecharts(this); + //linechartWidget->hide(); + + } + + + // Line chart + //if (!linechartWidget) + //{ + + // Center widgets + + //linechartWidget->addSystem(uas); + linechartWidget->addSource(mavlinkDecoder); - addCentralWidget(linechartWidget, tr("Realtime Plot")); - }*/ + //addCentralWidget(linechartWidget, tr("Realtime Plot")); + if (dataView->centralWidget() != linechartWidget) + { + dataView->setCentralWidget(linechartWidget); + linechartWidget->show(); + } + //dataView->setCentralWidget(linechartWidget); + //linechartWidget->show(); + //} // Load default custom widgets for this autopilot type loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName()); @@ -1551,7 +1717,7 @@ void MainWindow::UASCreated(UASInterface* uas) // Load last view if setting is present if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED")) { - int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt(); + /*int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt(); switch (view) { case VIEW_ENGINEER: @@ -1576,11 +1742,11 @@ void MainWindow::UASCreated(UASInterface* uas) default: loadOperatorView(); break; - } + }*/ } else { - loadOperatorView(); + // loadOperatorView(); } } @@ -1712,6 +1878,7 @@ void MainWindow::loadViewState() { if (widgetname != "") { + qDebug() << "Loading widget:" << widgetname; loadDockWidget(widgetname); } } @@ -1750,7 +1917,6 @@ void MainWindow::setAdvancedMode() QWidget *widget = i.key()->titleBarWidget(); i.key()->setTitleBarWidget(i.value()); dockToTitleBarMap[i.key()] = widget; - } } } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 1e65684f01119d252a489169b10553273dff86fb..cae4a267c97df67898e218c53eecc27651bc642d 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -119,6 +119,12 @@ public: return autoReconnect; } + /** @brief Get title bar mode setting */ + bool dockWidgetTitleBarsEnabled() + { + return dockWidgetTitleBarEnabled; + } + /** @brief Get low power mode setting */ bool lowPowerModeEnabled() { @@ -186,6 +192,8 @@ public slots: void reloadStylesheet(); /** @brief Let the user select the CSS style sheet */ void selectStylesheet(); + /** @breif Enable title bars on dock widgets when no in advanced mode */ + void enableDockWidgetTitleBars(bool enabled); /** @brief Automatically reconnect last link */ void enableAutoReconnect(bool enabled); /** @brief Save power by reducing update rates */ @@ -343,7 +351,7 @@ void createDockWidget(QWidget *parent,QWidget *child,QString title,QString objec QPointer simView; // Center widgets - //QPointer linechartWidget; + QPointer linechartWidget; //QPointer hudWidget; //QPointer configWidget; //QPointer mapWidget; @@ -436,6 +444,7 @@ private: QMap dockToTitleBarMap; QMap > centralWidgetToDockWidgetsMap; bool isAdvancedMode; + bool dockWidgetTitleBarEnabled; Ui::MainWindow ui; QString getWindowStateKey(); diff --git a/src/ui/QGCSettingsWidget.cc b/src/ui/QGCSettingsWidget.cc index 4bd74e58189648a0fe184df0c7e6c36ba28bbd73..f5fb0a6d0aadc5dd245c3a67b3073550fa0bdaab 100644 --- a/src/ui/QGCSettingsWidget.cc +++ b/src/ui/QGCSettingsWidget.cc @@ -42,6 +42,10 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) : ui->lowPowerCheckBox->setChecked(MainWindow::instance()->lowPowerModeEnabled()); connect(ui->lowPowerCheckBox, SIGNAL(clicked(bool)), MainWindow::instance(), SLOT(enableLowPowerMode(bool))); + //Dock widget title bars + ui->titleBarCheckBox->setChecked(MainWindow::instance()->dockWidgetTitleBarsEnabled()); + connect(ui->titleBarCheckBox,SIGNAL(clicked(bool)),MainWindow::instance(),SLOT(enableDockWidgetTitleBars(bool))); + // Style MainWindow::QGC_MAINWINDOW_STYLE style = (MainWindow::QGC_MAINWINDOW_STYLE)MainWindow::instance()->getStyle(); switch (style) { diff --git a/src/ui/QGCSettingsWidget.ui b/src/ui/QGCSettingsWidget.ui index 9a89b8fe7ca65a8ae5e186c3e13fbf21fd39c1c2..a26ae5f7badb048180b4892c539b12368e22d52e 100644 --- a/src/ui/QGCSettingsWidget.ui +++ b/src/ui/QGCSettingsWidget.ui @@ -46,7 +46,7 @@ - + Use native platform look and feel (Windows/Linux/Mac OS) @@ -56,14 +56,14 @@ - + Use indoor mission style (black background) - + Use outdoor mission style (light background) @@ -80,6 +80,16 @@ + + + + Show Docked Widget title bars when NOT in advanced Mode. + + + false + + + diff --git a/src/ui/designer/QGCComboBox.cc b/src/ui/designer/QGCComboBox.cc index c33d0f0d764d43a5d75df9547d3601e734128f03..bcd0d65f944354c11a5b4bc23e6135fc555d8335 100644 --- a/src/ui/designer/QGCComboBox.cc +++ b/src/ui/designer/QGCComboBox.cc @@ -154,7 +154,7 @@ void QGCComboBox::selectParameter(int paramIndex) if (uas->getParamManager()) { // Current value - uas->getParamManager()->requestParameterUpdate(component, parameterName); + //uas->getParamManager()->requestParameterUpdate(component, parameterName); // Minimum if (uas->getParamManager()->isParamMinKnown(parameterName)) diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index 857a8e1837e5118e4534b792d552362847c4a28a..5d37f4fb549a3cc120a2685b873f73b92a73656e 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -184,7 +184,7 @@ void QGCParamSlider::selectParameter(int paramIndex) if (uas->getParamManager()) { // Current value - uas->getParamManager()->requestParameterUpdate(component, parameterName); + //uas->getParamManager()->requestParameterUpdate(component, parameterName); // Minimum if (uas->getParamManager()->isParamMinKnown(parameterName)) diff --git a/src/ui/designer/QGCToolWidget.cc b/src/ui/designer/QGCToolWidget.cc index 84dd6aebcdf9b45bb3d351a75c761be2713777f3..7f976f68ae28352ac4a640f3b95a5b7d2df3061b 100644 --- a/src/ui/designer/QGCToolWidget.cc +++ b/src/ui/designer/QGCToolWidget.cc @@ -117,11 +117,13 @@ QList QGCToolWidget::createWidgetsFromSettings(QWidget* parent, { settings->setArrayIndex(i); QString name = settings->value("TITLE", "").toString(); + QString objname = settings->value("OBJECT_NAME", "").toString(); if (!instances()->contains(name) && name.length() != 0) { //qDebug() << "CREATED WIDGET:" << name; QGCToolWidget* tool = new QGCToolWidget(name, parent, settings); + tool->setObjectName(objname); newWidgets.append(tool); } else if (name.length() == 0) @@ -403,6 +405,7 @@ void QGCToolWidget::storeWidgetsToSettings(QString settingsFile) { settings->setArrayIndex(num++); settings->setValue("TITLE", instances()->values().at(i)->getTitle()); + settings->setValue("OBJECT_NAME", instances()->values().at(i)->objectName()); //qDebug() << "WRITING TITLE" << instances()->values().at(i)->getTitle(); } } diff --git a/src/ui/dockwidgettitlebareventfilter.cpp b/src/ui/dockwidgettitlebareventfilter.cpp new file mode 100644 index 0000000000000000000000000000000000000000..ca5951d7d6a0661a360eff4766e352cd7204207a --- /dev/null +++ b/src/ui/dockwidgettitlebareventfilter.cpp @@ -0,0 +1,15 @@ +#include "dockwidgettitlebareventfilter.h" +#include +#include +DockWidgetTitleBarEventFilter::DockWidgetTitleBarEventFilter(QObject *parent) : QObject(parent) +{ +} +bool DockWidgetTitleBarEventFilter::eventFilter(QObject *object,QEvent *event) +{ + qDebug() << event->type(); + if (event->type() == QEvent::MouseButtonPress || event->type() == QEvent::MouseButtonRelease) + { + return true; + } + return QObject::eventFilter(object,event); +} diff --git a/src/ui/dockwidgettitlebareventfilter.h b/src/ui/dockwidgettitlebareventfilter.h new file mode 100644 index 0000000000000000000000000000000000000000..d57edef1fb862711ba55d810b34614bc38dfad0f --- /dev/null +++ b/src/ui/dockwidgettitlebareventfilter.h @@ -0,0 +1,19 @@ +#ifndef DOCKWIDGETTITLEBAREVENTFILTER_H +#define DOCKWIDGETTITLEBAREVENTFILTER_H + +#include + +class DockWidgetTitleBarEventFilter : public QObject +{ + Q_OBJECT +public: + explicit DockWidgetTitleBarEventFilter(QObject *parent = 0); +protected: + bool eventFilter(QObject *object,QEvent *event); +signals: + +public slots: + +}; + +#endif // DOCKWIDGETTITLEBAREVENTFILTER_H diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index bafbab988688a3ee719803fe90d6ec49c08a1d7a..ad3920d0dcc9aa3a7c3c09e6c56ca1c41eb14751 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -9,7 +9,6 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : mapcontrol::OPMapWidget(parent), - currWPManager(NULL), firingWaypointChange(NULL), maxUpdateInterval(2.1f), // 2 seconds followUAVEnabled(false), @@ -17,17 +16,42 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : trailInterval(2.0f), followUAVID(0), mapInitialized(false), - homeAltitude(0) + homeAltitude(0), + uas(0) { + //currWPManager = new UASWaypointManager(NULL); //Create a waypoint manager that is null. + currWPManager = UASManager::instance()->getActiveUASWaypointManager(); + connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); + connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); + connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); + connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); + offlineMode = true; // Widget is inactive until shown defaultGuidedAlt = -1; loadSettings(false); this->setContextMenuPolicy(Qt::ActionsContextMenu); + QAction *guidedaction = new QAction(this); + guidedaction->setText("Go To Here (Guided Mode)"); + connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered())); + this->addAction(guidedaction); + guidedaction = new QAction(this); + guidedaction->setText("Go To Here Alt (Guided Mode)"); + connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered())); + this->addAction(guidedaction); + QAction *cameraaction = new QAction(this); + cameraaction->setText("Point Camera Here"); + connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered())); + this->addAction(cameraaction); } void QGCMapWidget::guidedActionTriggered() { + if (!uas) + { + QMessageBox::information(0,"Error","Please connect first"); + return; + } if (currWPManager) { if (defaultGuidedAlt == -1) @@ -49,6 +73,11 @@ void QGCMapWidget::guidedActionTriggered() } bool QGCMapWidget::guidedAltActionTriggered() { + if (!uas) + { + QMessageBox::information(0,"Error","Please connect first"); + return false; + } bool ok = false; int tmpalt = QInputDialog::getInt(this,"Altitude","Enter default altitude (in meters) of destination point for guided mode",100,0,30000,1,&ok); if (!ok) @@ -62,6 +91,11 @@ bool QGCMapWidget::guidedAltActionTriggered() } void QGCMapWidget::cameraActionTriggered() { + if (!uas) + { + QMessageBox::information(0,"Error","Please connect first"); + return; + } ArduPilotMegaMAV *newmav = qobject_cast(this->uas); if (newmav) { @@ -262,32 +296,14 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) if (uas) { + //UASWaypointManager *old = currWPManager; + currWPManager = uas->getWaypointManager(); - QList actionList = this->actions(); - for (int i=0;iremoveAction(actionList[i]); - actionList[i]->deleteLater(); - } - if (currWPManager->guidedModeSupported()) - { - QAction *guidedaction = new QAction(this); - guidedaction->setText("Go To Here (Guided Mode)"); - connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered())); - this->addAction(guidedaction); - guidedaction = new QAction(this); - guidedaction->setText("Go To Here Alt (Guided Mode)"); - connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered())); - this->addAction(guidedaction); - - if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) - { - QAction *cameraaction = new QAction(this); - cameraaction->setText("Point Camera Here"); - connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered())); - this->addAction(cameraaction); - } - } + + updateSelectedSystem(uas->getUASID()); + followUAVID = uas->getUASID(); + + updateWaypointList(uas->getUASID()); // Connect the waypoint manager / data storage to the UI connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); @@ -295,11 +311,27 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); - updateSelectedSystem(uas->getUASID()); - followUAVID = uas->getUASID(); + /*if (offlineMode) + { + + if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes) + { + //Need to transfer all waypoints from the offline mode WPManager to the online mode. + for (int i=0;igetWaypointEditableList().size();i++) + { + Waypoint *wp = currWPManager->createWaypoint(); + wp->setLatitude(old->getWaypointEditableList()[i]->getLatitude()); + wp->setLongitude(old->getWaypointEditableList()[i]->getLongitude()); + wp->setAltitude(old->getWaypointEditableList()[i]->getAltitude()); + } + } + offlineMode = false; + old->deleteLater(); + }*/ + // Delete all waypoints and add waypoint from new system - updateWaypointList(uas->getUASID()); + } } @@ -563,7 +595,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) // Currently only accept waypoint updates from the UAS in focus // this has to be changed to accept read-only updates from other systems as well. UASInterface* uasInstance = UASManager::instance()->getUASForId(uas); - if (uasInstance->getWaypointManager() == currWPManager || uas == -1) + if (!uasInstance || uasInstance->getWaypointManager() == currWPManager || uas == -1) { // Only accept waypoints in global coordinate frame if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType()) diff --git a/src/ui/map/QGCMapWidget.h b/src/ui/map/QGCMapWidget.h index 997976c2febe6ca821e4e2f27d7e49f388dd8496..d6f3b53d790be4564280fb1330423f46a0190736 100644 --- a/src/ui/map/QGCMapWidget.h +++ b/src/ui/map/QGCMapWidget.h @@ -137,6 +137,7 @@ protected: void mouseDoubleClickEvent(QMouseEvent* event); UASWaypointManager* currWPManager; ///< The current waypoint manager + bool offlineMode; QMap waypointsToIcons; QMap iconsToWaypoints; Waypoint* firingWaypointChange; diff --git a/src/ui/uas/UASQuickView.cc b/src/ui/uas/UASQuickView.cc new file mode 100644 index 0000000000000000000000000000000000000000..5edd0aa76ff43ac87f292e585fc85db46b1cda87 --- /dev/null +++ b/src/ui/uas/UASQuickView.cc @@ -0,0 +1,169 @@ +#include "UASQuickView.h" +#include +#include +UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent) +{ + ui.setupUi(this); + connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(setActiveUAS(UASInterface*))); + connect(UASManager::instance(),SIGNAL(UASCreated(UASInterface*)),this,SLOT(addUAS(UASInterface*))); + if (UASManager::instance()->getActiveUAS()) + { + addUAS(UASManager::instance()->getActiveUAS()); + } + this->setContextMenuPolicy(Qt::ActionsContextMenu); + + + { + QAction *action = new QAction("latitude",this); + action->setCheckable(true); + action->setChecked(true); + connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool))); + this->addAction(action); + UASQuickViewItem *item = new UASQuickViewItem(this); + item->setTitle("latitude"); + ui.verticalLayout->addWidget(item); + uasPropertyToLabelMap["latitude"] = item; + } + + { + QAction *action = new QAction("longitude",this); + action->setCheckable(true); + action->setChecked(true); + connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool))); + this->addAction(action); + UASQuickViewItem *item = new UASQuickViewItem(this); + item->setTitle("longitude"); + ui.verticalLayout->addWidget(item); + uasPropertyToLabelMap["longitude"] = item; + } + + { + QAction *action = new QAction("altitude",this); + action->setCheckable(true); + action->setChecked(true); + connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool))); + this->addAction(action); + UASQuickViewItem *item = new UASQuickViewItem(this); + item->setTitle("altitude"); + ui.verticalLayout->addWidget(item); + uasPropertyToLabelMap["altitude"] = item; + } + + { + QAction *action = new QAction("satelliteCount",this); + action->setCheckable(true); + action->setChecked(true); + connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool))); + this->addAction(action); + UASQuickViewItem *item = new UASQuickViewItem(this); + item->setTitle("satelliteCount"); + ui.verticalLayout->addWidget(item); + uasPropertyToLabelMap["satelliteCount"] = item; + } + + { + QAction *action = new QAction("distToWaypoint",this); + action->setCheckable(true); + action->setChecked(true); + connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool))); + this->addAction(action); + UASQuickViewItem *item = new UASQuickViewItem(this); + item->setTitle("distToWaypoint"); + ui.verticalLayout->addWidget(item); + uasPropertyToLabelMap["distToWaypoint"] = item; + } + + updateTimer = new QTimer(this); + connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick())); + updateTimer->start(1000); +} +void UASQuickView::updateTimerTick() +{ + for (int i=0;isetValue(uasPropertyValueMap.value(uasPropertyList[i],0)); + } + } +} + +void UASQuickView::addUAS(UASInterface* uas) +{ + if (uas) + { + if (!this->uas) + { + setActiveUAS(uas); + } + } +} + +void UASQuickView::setActiveUAS(UASInterface* uas) +{ + if (!uas) + { + return; + } + this->uas = uas; + connect(uas,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64))); + uasPropertyList.clear(); + qDebug() << "UASInfoWidget property count:" << uas->metaObject()->propertyCount(); + for (int i=0;imetaObject()->propertyCount();i++) + { + if (uas->metaObject()->property(i).hasNotifySignal()) + { + qDebug() << "Property:" << i << uas->metaObject()->property(i).name(); + uasPropertyList.append(uas->metaObject()->property(i).name()); + if (!uasPropertyToLabelMap.contains(uas->metaObject()->property(i).name())) + { + QAction *action = new QAction(QString(uas->metaObject()->property(i).name()),this); + action->setCheckable(true); + connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool))); + this->addAction(action); + } + qDebug() << "Signature:" << uas->metaObject()->property(i).notifySignal().signature(); + int val = this->metaObject()->indexOfMethod("valChanged(double,QString)"); + if (val != -1) + { + + if (!connect(uas,uas->metaObject()->property(i).notifySignal(),this,this->metaObject()->method(val))) + { + qDebug() << "Error connecting signal"; + } + } + } + } +} +void UASQuickView::actionTriggered(bool checked) +{ + QAction *senderlabel = qobject_cast(sender()); + if (!senderlabel) + { + return; + } + if (checked) + { + UASQuickViewItem *item = new UASQuickViewItem(this); + item->setTitle(senderlabel->text()); + ui.verticalLayout->addWidget(item); + uasPropertyToLabelMap[senderlabel->text()] = item; + } + else + { + ui.verticalLayout->removeWidget(uasPropertyToLabelMap[senderlabel->text()]); + uasPropertyToLabelMap[senderlabel->text()]->deleteLater(); + uasPropertyToLabelMap.remove(senderlabel->text()); + + } +} +void UASQuickView::valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs) +{ + uasPropertyValueMap[name] = value.toDouble(); +} + +void UASQuickView::valChanged(double val,QString type) +{ + //qDebug() << "Value changed:" << type << val; + // uasPropertyValueMap[type] = val; +} diff --git a/src/ui/uas/UASQuickView.h b/src/ui/uas/UASQuickView.h new file mode 100644 index 0000000000000000000000000000000000000000..7a06fecad24b006236030c46ed7bec7b5381f6b2 --- /dev/null +++ b/src/ui/uas/UASQuickView.h @@ -0,0 +1,35 @@ +#ifndef UASQUICKVIEW_H +#define UASQUICKVIEW_H + +#include +#include +#include +#include "uas/UASManager.h" +#include "uas/UASInterface.h" +#include "ui_UASQuickView.h" +#include "UASQuickViewItem.h" +class UASQuickView : public QWidget +{ + Q_OBJECT +public: + UASQuickView(QWidget *parent = 0); +private: + UASInterface *uas; + QList uasPropertyList; + QMap uasPropertyValueMap; + QMap uasPropertyToLabelMap; + QTimer *updateTimer; +protected: + Ui::Form ui; +signals: + +public slots: + void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs); + void actionTriggered(bool checked); + void updateTimerTick(); + void addUAS(UASInterface* uas); + void setActiveUAS(UASInterface* uas); + void valChanged(double val,QString type); +}; + +#endif // UASQUICKVIEW_H diff --git a/src/ui/uas/UASQuickView.ui b/src/ui/uas/UASQuickView.ui new file mode 100644 index 0000000000000000000000000000000000000000..19e3272ecc7a3629b00c27d134c7df04c898fbdb --- /dev/null +++ b/src/ui/uas/UASQuickView.ui @@ -0,0 +1,30 @@ + + + Form + + + + 0 + 0 + 400 + 300 + + + + + 100 + 100 + + + + Form + + + + + + + + + + diff --git a/src/ui/uas/UASQuickViewItem.cc b/src/ui/uas/UASQuickViewItem.cc new file mode 100644 index 0000000000000000000000000000000000000000..6c075c64dc3db60acba1b6522acf029c2bfc5833 --- /dev/null +++ b/src/ui/uas/UASQuickViewItem.cc @@ -0,0 +1,26 @@ +#include "UASQuickViewItem.h" +#include + +UASQuickViewItem::UASQuickViewItem(QWidget *parent) : QWidget(parent) +{ + QVBoxLayout *layout = new QVBoxLayout(); + this->setLayout(layout); + titleLabel = new QLabel(this); + titleLabel->setAlignment(Qt::AlignHCenter); + this->layout()->addWidget(titleLabel); + valueLabel = new QLabel(this); + valueLabel->setAlignment(Qt::AlignHCenter); + valueLabel->setText("

0.00

"); + this->layout()->addWidget(valueLabel); + layout->addSpacerItem(new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding)); +} + +void UASQuickViewItem::setValue(double value) +{ + valueLabel->setText("

" + QString::number(value,'f',4) + "

"); +} + +void UASQuickViewItem::setTitle(QString title) +{ + titleLabel->setText(title); +} diff --git a/src/ui/uas/UASQuickViewItem.h b/src/ui/uas/UASQuickViewItem.h new file mode 100644 index 0000000000000000000000000000000000000000..d6b1b12e0d0188a657fbe6a17557810234cfb88b --- /dev/null +++ b/src/ui/uas/UASQuickViewItem.h @@ -0,0 +1,22 @@ +#ifndef UASQUICKVIEWITEM_H +#define UASQUICKVIEWITEM_H + +#include +#include +class UASQuickViewItem : public QWidget +{ + Q_OBJECT +public: + explicit UASQuickViewItem(QWidget *parent = 0); + void setValue(double value); + void setTitle(QString title); +private: + QLabel *titleLabel; + QLabel *valueLabel; +signals: + +public slots: + +}; + +#endif // UASQUICKVIEWITEM_H