From b991f98a2da65ade79c795a5d54d85f0eaf81dbb Mon Sep 17 00:00:00 2001 From: dogmaphobic Date: Mon, 4 May 2015 08:15:33 -0400 Subject: [PATCH] Refactoring QGCFlightDisplay and Renaming QGCMavManager.* Sorting source and headers while at it. --- QGCApplication.pro | 12 +- src/QGCApplication.cc | 2 +- src/QmlControls/MavManager.cc | 626 +++++++++++++++++++++++++++++++ src/QmlControls/MavManager.h | 215 +++++++++++ src/QmlControls/QGCMavManager.cc | 626 ------------------------------- src/QmlControls/QGCMavManager.h | 215 ----------- src/ui/MainWindow.cc | 6 +- src/ui/MainWindow.h | 6 +- src/ui/flightdisplay/FlightDisplay.cc | 77 ++++ src/ui/flightdisplay/FlightDisplay.h | 55 +++ src/ui/flightdisplay/QGCFlightDisplay.cc | 77 ---- src/ui/flightdisplay/QGCFlightDisplay.h | 55 --- src/ui/toolbar/MainToolBar.cc | 4 +- 13 files changed, 988 insertions(+), 988 deletions(-) create mode 100644 src/QmlControls/MavManager.cc create mode 100644 src/QmlControls/MavManager.h delete mode 100644 src/QmlControls/QGCMavManager.cc delete mode 100644 src/QmlControls/QGCMavManager.h create mode 100644 src/ui/flightdisplay/FlightDisplay.cc create mode 100644 src/ui/flightdisplay/FlightDisplay.h delete mode 100644 src/ui/flightdisplay/QGCFlightDisplay.cc delete mode 100644 src/ui/flightdisplay/QGCFlightDisplay.h diff --git a/QGCApplication.pro b/QGCApplication.pro index aa4f0c2..26b28f9 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -263,6 +263,7 @@ HEADERS += \ src/QGCQuickWidget.h \ src/QGCSingleton.h \ src/QGCTemporaryFile.h \ + src/QmlControls/MavManager.h \ src/QmlControls/ParameterEditorController.h \ src/QmlControls/ScreenTools.h \ src/uas/QGCMAVLinkUASFactory.h \ @@ -278,7 +279,7 @@ HEADERS += \ src/ui/configuration/SerialSettingsDialog.h \ src/ui/configuration/terminalconsole.h \ src/ui/DebugConsole.h \ - src/ui/flightdisplay/QGCFlightDisplay.h \ + src/ui/flightdisplay/FlightDisplay.h \ src/ui/HDDisplay.h \ src/ui/HSIDisplay.h \ src/ui/HUD.h \ @@ -351,12 +352,11 @@ HEADERS += \ src/ui/WaypointEditableView.h \ src/ui/WaypointList.h \ src/ui/WaypointViewOnlyView.h \ - src/ViewWidgets/ParameterEditorWidget.h \ src/ViewWidgets/CustomCommandWidget.h \ src/ViewWidgets/CustomCommandWidgetController.h \ + src/ViewWidgets/ParameterEditorWidget.h \ src/ViewWidgets/ViewWidgetController.h \ src/Waypoint.h \ - src/QmlControls/QGCMavManager.h !AndroidBuild { HEADERS += \ @@ -395,6 +395,7 @@ SOURCES += \ src/QGCQuickWidget.cc \ src/QGCSingleton.cc \ src/QGCTemporaryFile.cc \ + src/QmlControls/MavManager.cc \ src/QmlControls/ParameterEditorController.cc \ src/QmlControls/ScreenTools.cc \ src/uas/QGCMAVLinkUASFactory.cc \ @@ -408,7 +409,7 @@ SOURCES += \ src/ui/configuration/SerialSettingsDialog.cc \ src/ui/configuration/terminalconsole.cpp \ src/ui/DebugConsole.cc \ - src/ui/flightdisplay/QGCFlightDisplay.cc \ + src/ui/flightdisplay/FlightDisplay.cc \ src/ui/HDDisplay.cc \ src/ui/HSIDisplay.cc \ src/ui/HUD.cc \ @@ -481,12 +482,11 @@ SOURCES += \ src/ui/WaypointEditableView.cc \ src/ui/WaypointList.cc \ src/ui/WaypointViewOnlyView.cc \ - src/ViewWidgets/ParameterEditorWidget.cc \ src/ViewWidgets/CustomCommandWidget.cc \ src/ViewWidgets/CustomCommandWidgetController.cc \ + src/ViewWidgets/ParameterEditorWidget.cc \ src/ViewWidgets/ViewWidgetController.cc \ src/Waypoint.cc \ - src/QmlControls/QGCMavManager.cc !AndroidBuild { SOURCES += \ diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index e9a4f0e..ce28f88 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -64,7 +64,7 @@ #include "CustomCommandWidgetController.h" #include "ScreenTools.h" -#include "QGCMavManager.h" +#include "MavManager.h" #ifdef QGC_RTLAB_ENABLED #include "OpalLink.h" diff --git a/src/QmlControls/MavManager.cc b/src/QmlControls/MavManager.cc new file mode 100644 index 0000000..566176f --- /dev/null +++ b/src/QmlControls/MavManager.cc @@ -0,0 +1,626 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2015 QGROUNDCONTROL PROJECT + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * @brief QGC Mav Manager (QML Bindings) + * @author Gus Grubba + */ + +#include "MainWindow.h" +#include "UASManager.h" +#include "Waypoint.h" +#include "MavManager.h" + +#define UPDATE_TIMER 50 +#define DEFAULT_LAT 38.965767f +#define DEFAULT_LON -120.083923f + +MavManager::MavManager(QObject *parent) + : QObject(parent) + , _mav(NULL) + , _roll(0.0f) + , _pitch(0.0f) + , _heading(0.0f) + , _altitudeAMSL(0.0f) + , _altitudeWGS84(0.0f) + , _altitudeRelative(0.0f) + , _groundSpeed(0.0f) + , _airSpeed(0.0f) + , _climbRate(0.0f) + , _navigationAltitudeError(0.0f) + , _navigationSpeedError(0.0f) + , _navigationCrosstrackError(0.0f) + , _navigationTargetBearing(0.0f) + , _latitude(DEFAULT_LAT) + , _longitude(DEFAULT_LON) + , _refreshTimer(new QTimer(this)) + , _batteryVoltage(0.0) + , _batteryPercent(0.0) + , _systemArmed(false) + , _currentHeartbeatTimeout(0) + , _waypointDistance(0.0) + , _currentWaypoint(0) + , _satelliteCount(-1) + , _satelliteLock(0) + , _wpm(NULL) + , _updateCount(0) +{ + // Connect with UAS signal + _setActiveUAS(UASManager::instance()->getActiveUAS()); + connect(UASManager::instance(), SIGNAL(UASDeleted(UASInterface*)), this, SLOT(_forgetUAS(UASInterface*))); + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(_setActiveUAS(UASInterface*))); + // Refresh timer + connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate())); + _refreshTimer->setInterval(UPDATE_TIMER); + _refreshTimer->start(UPDATE_TIMER); + emit heartbeatTimeoutChanged(); +} + +MavManager::~MavManager() +{ + _refreshTimer->stop(); +} + +void MavManager::saveSetting(const QString &name, const QString& value) +{ + QSettings settings; + settings.setValue(name, value); +} + +QString MavManager::loadSetting(const QString &name, const QString& defaultValue) +{ + QSettings settings; + return settings.value(name, defaultValue).toString(); +} + +void MavManager::_forgetUAS(UASInterface* uas) +{ + if (_mav != NULL && _mav == uas) { + // Disconnect any previously connected active MAV + disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); + disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); + disconnect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); + disconnect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); + disconnect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); + disconnect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString))); + disconnect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool))); + disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); + disconnect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); + disconnect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); + disconnect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); + disconnect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); + disconnect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); + disconnect(_mav, &UASInterface::localizationChanged, this, &MavManager::_setSatLoc); + if (_wpm) { + disconnect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &MavManager::_updateCurrentWaypoint); + disconnect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &MavManager::_updateWaypointDistance); + disconnect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); + disconnect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); + } + UAS* pUas = dynamic_cast(_mav); + if(pUas) { + disconnect(pUas, &UAS::satelliteCountChanged, this, &MavManager::_setSatelliteCount); + } + _mav = NULL; + _satelliteCount = -1; + emit mavPresentChanged(); + emit satelliteCountChanged(); + } +} + +void MavManager::_setActiveUAS(UASInterface* uas) +{ + if (uas == _mav) + return; + // Disconnect the previous one (if any) + if(_mav) { + _forgetUAS(_mav); + } + if (uas) { + // Reset satellite count (no GPS) + _satelliteCount = -1; + emit satelliteCountChanged(); + // Reset connection lost (if any) + _currentHeartbeatTimeout = 0; + emit heartbeatTimeoutChanged(); + // Set new UAS + _mav = uas; + // Now connect the new UAS + connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); + connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); + connect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); + connect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); + connect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); + connect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString))); + connect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool))); + connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); + connect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); + connect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); + connect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); + connect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); + connect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); + connect(_mav, &UASInterface::localizationChanged, this, &MavManager::_setSatLoc); + _wpm = _mav->getWaypointManager(); + if (_wpm) { + connect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &MavManager::_updateCurrentWaypoint); + connect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &MavManager::_updateWaypointDistance); + connect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); + connect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)),this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); + _wpm->readWaypoints(true); + } + UAS* pUas = dynamic_cast(_mav); + if(pUas) { + _setSatelliteCount(pUas->getSatelliteCount(), QString("")); + connect(pUas, &UAS::satelliteCountChanged, this, &MavManager::_setSatelliteCount); + } + _setSystemType(_mav, _mav->getSystemType()); + _updateArmingState(_mav->isArmed()); + } + emit mavPresentChanged(); +} + +void MavManager::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64) +{ + if (isinf(roll)) { + _roll = std::numeric_limits::quiet_NaN(); + } else { + float rolldeg = _oneDecimal(roll * (180.0 / M_PI)); + if (fabs(roll - rolldeg) > 1.0) { + _roll = rolldeg; + if(_refreshTimer->isActive()) { + emit rollChanged(); + } + } + if(_roll != rolldeg) { + _roll = rolldeg; + _addChange(ROLL_CHANGED); + } + } + if (isinf(pitch)) { + _pitch = std::numeric_limits::quiet_NaN(); + } else { + float pitchdeg = _oneDecimal(pitch * (180.0 / M_PI)); + if (fabs(pitch - pitchdeg) > 1.0) { + _pitch = pitchdeg; + if(_refreshTimer->isActive()) { + emit pitchChanged(); + } + } + if(_pitch != pitchdeg) { + _pitch = pitchdeg; + _addChange(PITCH_CHANGED); + } + } + if (isinf(yaw)) { + _heading = std::numeric_limits::quiet_NaN(); + } else { + yaw = _oneDecimal(yaw * (180.0 / M_PI)); + if (yaw < 0) yaw += 360; + if (fabs(_heading - yaw) > 1.0) { + _heading = yaw; + if(_refreshTimer->isActive()) { + emit headingChanged(); + } + } + if(_heading != yaw) { + _heading = yaw; + _addChange(HEADING_CHANGED); + } + } +} + +void MavManager::_updateAttitude(UASInterface* uas, int, double roll, double pitch, double yaw, quint64 timestamp) +{ + _updateAttitude(uas, roll, pitch, yaw, timestamp); +} + +void MavManager::_updateSpeed(UASInterface*, double groundSpeed, double airSpeed, quint64) +{ + groundSpeed = _oneDecimal(groundSpeed); + if (fabs(_groundSpeed - groundSpeed) > 0.5) { + _groundSpeed = groundSpeed; + if(_refreshTimer->isActive()) { + emit groundSpeedChanged(); + } + } + airSpeed = _oneDecimal(airSpeed); + if (fabs(_airSpeed - airSpeed) > 1.0) { + _airSpeed = airSpeed; + if(_refreshTimer->isActive()) { + emit airSpeedChanged(); + } + } + if(_groundSpeed != groundSpeed) { + _groundSpeed = groundSpeed; + _addChange(GROUNDSPEED_CHANGED); + } + if(_airSpeed != airSpeed) { + _airSpeed = airSpeed; + _addChange(AIRSPEED_CHANGED); + } +} + +void MavManager::_updateAltitude(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64) { + altitudeAMSL = _oneDecimal(altitudeAMSL); + if (fabs(_altitudeAMSL - altitudeAMSL) > 0.5) { + _altitudeAMSL = altitudeAMSL; + if(_refreshTimer->isActive()) { + emit altitudeAMSLChanged(); + } + } + altitudeWGS84 = _oneDecimal(altitudeWGS84); + if (fabs(_altitudeWGS84 - altitudeWGS84) > 0.5) { + _altitudeWGS84 = altitudeWGS84; + if(_refreshTimer->isActive()) { + emit altitudeWGS84Changed(); + } + } + altitudeRelative = _oneDecimal(altitudeRelative); + if (fabs(_altitudeRelative - altitudeRelative) > 0.5) { + _altitudeRelative = altitudeRelative; + if(_refreshTimer->isActive()) { + emit altitudeRelativeChanged(); + } + } + climbRate = _oneDecimal(climbRate); + if (fabs(_climbRate - climbRate) > 0.5) { + _climbRate = climbRate; + if(_refreshTimer->isActive()) { + emit climbRateChanged(); + } + } + if(_altitudeAMSL != altitudeAMSL) { + _altitudeAMSL = altitudeAMSL; + _addChange(ALTITUDEAMSL_CHANGED); + } + if(_altitudeWGS84 != altitudeWGS84) { + _altitudeWGS84 = altitudeWGS84; + _addChange(ALTITUDEWGS84_CHANGED); + } + if(_altitudeRelative != altitudeRelative) { + _altitudeRelative = altitudeRelative; + _addChange(ALTITUDERELATIVE_CHANGED); + } + if(_climbRate != climbRate) { + _climbRate = climbRate; + _addChange(CLIMBRATE_CHANGED); + } +} + +void MavManager::_updateNavigationControllerErrors(UASInterface*, double altitudeError, double speedError, double xtrackError) { + _navigationAltitudeError = altitudeError; + _navigationSpeedError = speedError; + _navigationCrosstrackError = xtrackError; +} + +void MavManager::_updateNavigationControllerData(UASInterface *uas, float, float, float, float targetBearing, float) { + if (_mav == uas) { + _navigationTargetBearing = targetBearing; + } +} + +/* + * Internal + */ + +bool MavManager::_isAirplane() { + if (_mav) + return _mav->isAirplane(); + return false; +} + +void MavManager::_addChange(int id) +{ + if(!_changes.contains(id)) { + _changes.append(id); + } +} + +float MavManager::_oneDecimal(float value) +{ + int i = (value * 10); + return (float)i / 10.0; +} + +void MavManager::_checkUpdate() +{ + // Update current location + if(_mav) { + if(_latitude != _mav->getLatitude()) { + _latitude = _mav->getLatitude(); + emit latitudeChanged(); + } + if(_longitude != _mav->getLongitude()) { + _longitude = _mav->getLongitude(); + emit longitudeChanged(); + } + } + // The timer rate is 20Hz for the coordinates above. These below we only check + // twice a second. + if(++_updateCount > 9) { + _updateCount = 0; + // Check for changes + // Significant changes, that is, whole number changes, are updated immediatelly. + // For every message however, we set a flag for what changed and this timer updates + // them to bring everything up-to-date. This prevents an avalanche of UI updates. + foreach(int i, _changes) { + switch (i) { + case ROLL_CHANGED: + emit rollChanged(); + break; + case PITCH_CHANGED: + emit pitchChanged(); + break; + case HEADING_CHANGED: + emit headingChanged(); + break; + case GROUNDSPEED_CHANGED: + emit groundSpeedChanged(); + break; + case AIRSPEED_CHANGED: + emit airSpeedChanged(); + break; + case CLIMBRATE_CHANGED: + emit climbRateChanged(); + break; + case ALTITUDERELATIVE_CHANGED: + emit altitudeRelativeChanged(); + break; + case ALTITUDEWGS84_CHANGED: + emit altitudeWGS84Changed(); + break; + case ALTITUDEAMSL_CHANGED: + emit altitudeAMSLChanged(); + break; + default: + break; + } + } + _changes.clear(); + } +} + +QString MavManager::getMavIconColor() +{ + // TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette + if(_mav) + return _mav->getColor().name(); + else + return QString("black"); +} + +void MavManager::_updateArmingState(bool armed) +{ + if(_systemArmed != armed) { + _systemArmed = armed; + emit systemArmedChanged(); + } +} + +void MavManager::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int) +{ + + if(percent < 0.0) { + percent = 0.0; + } + if(voltage < 0.0) { + voltage = 0.0; + } + if (_batteryVoltage != voltage) { + _batteryVoltage = voltage; + emit batteryVoltageChanged(); + } + if (_batteryPercent != percent) { + _batteryPercent = percent; + emit batteryPercentChanged(); + } +} + +void MavManager::_updateState(UASInterface*, QString name, QString) +{ + if (_currentState != name) { + _currentState = name; + emit currentStateChanged(); + } +} + +void MavManager::_updateMode(int, QString name, QString) +{ + if (name.size()) { + QString shortMode = name; + shortMode = shortMode.replace("D|", ""); + shortMode = shortMode.replace("A|", ""); + if (_currentMode != shortMode) { + _currentMode = shortMode; + emit currentModeChanged(); + } + } +} + +void MavManager::_updateName(const QString& name) +{ + if (_systemName != name) { + _systemName = name; + emit systemNameChanged(); + } +} + +/** + * The current system type is represented through the system icon. + * + * @param uas Source system, has to be the same as this->uas + * @param systemType type ID, following the MAVLink system type conventions + * @see http://pixhawk.ethz.ch/software/mavlink + */ +void MavManager::_setSystemType(UASInterface*, unsigned int systemType) +{ + _systemPixmap = "qrc:/res/mavs/"; + switch (systemType) { + case MAV_TYPE_GENERIC: + _systemPixmap += "Generic"; + break; + case MAV_TYPE_FIXED_WING: + _systemPixmap += "FixedWing"; + break; + case MAV_TYPE_QUADROTOR: + _systemPixmap += "QuadRotor"; + break; + case MAV_TYPE_COAXIAL: + _systemPixmap += "Coaxial"; + break; + case MAV_TYPE_HELICOPTER: + _systemPixmap += "Helicopter"; + break; + case MAV_TYPE_ANTENNA_TRACKER: + _systemPixmap += "AntennaTracker"; + break; + case MAV_TYPE_GCS: + _systemPixmap += "Groundstation"; + break; + case MAV_TYPE_AIRSHIP: + _systemPixmap += "Airship"; + break; + case MAV_TYPE_FREE_BALLOON: + _systemPixmap += "FreeBalloon"; + break; + case MAV_TYPE_ROCKET: + _systemPixmap += "Rocket"; + break; + case MAV_TYPE_GROUND_ROVER: + _systemPixmap += "GroundRover"; + break; + case MAV_TYPE_SURFACE_BOAT: + _systemPixmap += "SurfaceBoat"; + break; + case MAV_TYPE_SUBMARINE: + _systemPixmap += "Submarine"; + break; + case MAV_TYPE_HEXAROTOR: + _systemPixmap += "HexaRotor"; + break; + case MAV_TYPE_OCTOROTOR: + _systemPixmap += "OctoRotor"; + break; + case MAV_TYPE_TRICOPTER: + _systemPixmap += "TriCopter"; + break; + case MAV_TYPE_FLAPPING_WING: + _systemPixmap += "FlappingWing"; + break; + case MAV_TYPE_KITE: + _systemPixmap += "Kite"; + break; + default: + _systemPixmap += "Unknown"; + break; + } + emit systemPixmapChanged(); +} + +void MavManager::_heartbeatTimeout(bool timeout, unsigned int ms) +{ + unsigned int elapsed = ms; + if (!timeout) + { + elapsed = 0; + } + if(elapsed != _currentHeartbeatTimeout) { + _currentHeartbeatTimeout = elapsed; + emit heartbeatTimeoutChanged(); + } +} + +void MavManager::_setSatelliteCount(double val, QString) +{ + // I'm assuming that a negative value or over 99 means there is no GPS + if(val < 0.0) val = -1.0; + if(val > 99.0) val = -1.0; + if(_satelliteCount != (int)val) { + _satelliteCount = (int)val; + emit satelliteCountChanged(); + } +} + +void MavManager::_setSatLoc(UASInterface*, int fix) +{ + // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock + if(_satelliteLock != fix) { + _satelliteLock = fix; + emit satelliteLockChanged(); + } +} + +void MavManager::_updateWaypointDistance(double distance) +{ + if (_waypointDistance != distance) { + _waypointDistance = distance; + emit waypointDistanceChanged(); + } +} + +void MavManager::_updateCurrentWaypoint(quint16 id) +{ + if (_currentWaypoint != id) { + _currentWaypoint = id; + emit currentWaypointChanged(); + } +} + +void MavManager::_updateWaypointViewOnly(int, Waypoint* /*wp*/) +{ + /* + bool changed = false; + for(int i = 0; i < _waypoints.count(); i++) { + if(_waypoints[i].getId() == wp->getId()) { + _waypoints[i] = *wp; + changed = true; + break; + } + } + if(changed) { + emit waypointListChanged(); + } + */ +} + +void MavManager::_waypointViewOnlyListChanged() +{ + if(_wpm) { + const QList &waypoints = _wpm->getWaypointViewOnlyList(); + _waypoints.clear(); + for(int i = 0; i < waypoints.count(); i++) { + Waypoint* wp = waypoints[i]; + _waypoints.append(new Waypoint(*wp)); + } + emit waypointsChanged(); + /* + if(_longitude == DEFAULT_LON && _latitude == DEFAULT_LAT && _waypoints.length()) { + _longitude = _waypoints[0]->getLongitude(); + _latitude = _waypoints[0]->getLatitude(); + emit longitudeChanged(); + emit latitudeChanged(); + } + */ + } +} diff --git a/src/QmlControls/MavManager.h b/src/QmlControls/MavManager.h new file mode 100644 index 0000000..56b25a3 --- /dev/null +++ b/src/QmlControls/MavManager.h @@ -0,0 +1,215 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2015 QGROUNDCONTROL PROJECT + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * @brief QGC Mav Manager (QML Bindings) + * @author Gus Grubba + */ + +#ifndef MAVMANAGER_H +#define MAVMANAGER_H + +#include +#include +#include +#include "Waypoint.h" + +class UASInterface; +class UASWaypointManager; + +class MavManager : public QObject +{ + Q_OBJECT + Q_ENUMS(MessageType_t) +public: + explicit MavManager(QObject *parent = 0); + ~MavManager(); + + enum { + ROLL_CHANGED, + PITCH_CHANGED, + HEADING_CHANGED, + GROUNDSPEED_CHANGED, + AIRSPEED_CHANGED, + CLIMBRATE_CHANGED, + ALTITUDERELATIVE_CHANGED, + ALTITUDEWGS84_CHANGED, + ALTITUDEAMSL_CHANGED + }; + + Q_INVOKABLE QString getMavIconColor(); + Q_INVOKABLE void saveSetting (const QString &key, const QString& value); + Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); + + Q_PROPERTY(float roll READ roll NOTIFY rollChanged) + Q_PROPERTY(float pitch READ pitch NOTIFY pitchChanged) + Q_PROPERTY(float heading READ heading NOTIFY headingChanged) + Q_PROPERTY(float groundSpeed READ groundSpeed NOTIFY groundSpeedChanged) + Q_PROPERTY(float airSpeed READ airSpeed NOTIFY airSpeedChanged) + Q_PROPERTY(float climbRate READ climbRate NOTIFY climbRateChanged) + Q_PROPERTY(float altitudeRelative READ altitudeRelative NOTIFY altitudeRelativeChanged) + Q_PROPERTY(float altitudeWGS84 READ altitudeWGS84 NOTIFY altitudeWGS84Changed) + Q_PROPERTY(float altitudeAMSL READ altitudeAMSL NOTIFY altitudeAMSLChanged) + Q_PROPERTY(float latitude READ latitude NOTIFY latitudeChanged) + Q_PROPERTY(float longitude READ longitude NOTIFY longitudeChanged) + Q_PROPERTY(bool mavPresent READ mavPresent NOTIFY mavPresentChanged) + Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) + Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) + Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged) + Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged) + Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged) + Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged) + Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) + Q_PROPERTY(QString systemName READ systemName NOTIFY systemNameChanged) + Q_PROPERTY(int satelliteLock READ satelliteLock NOTIFY satelliteLockChanged) + Q_PROPERTY(double waypointDistance READ waypointDistance NOTIFY waypointDistanceChanged) + Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged) + Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) + Q_PROPERTY(QQmlListProperty waypoints READ waypoints NOTIFY waypointsChanged) + + float roll () { return _roll; } + float pitch () { return _pitch; } + float heading () { return _heading; } + float groundSpeed () { return _groundSpeed; } + float airSpeed () { return _airSpeed; } + float climbRate () { return _climbRate; } + float altitudeRelative () { return _altitudeRelative; } + float altitudeWGS84 () { return _altitudeWGS84; } + float altitudeAMSL () { return _altitudeAMSL; } + float latitude () { return _latitude; } + float longitude () { return _longitude; } + bool mavPresent () { return _mav != NULL; } + int satelliteCount () { return _satelliteCount; } + double batteryVoltage () { return _batteryVoltage; } + double batteryPercent () { return _batteryPercent; } + bool systemArmed () { return _systemArmed; } + QString currentMode () { return _currentMode; } + QString systemPixmap () { return _systemPixmap; } + QString currentState () { return _currentState; } + QString systemName () { return _systemName; } + int satelliteLock () { return _satelliteLock; } + double waypointDistance () { return _waypointDistance; } + uint16_t currentWaypoint () { return _currentWaypoint; } + unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } + + QQmlListProperty waypoints() {return QQmlListProperty(this, _waypoints); } + +signals: + void rollChanged (); + void pitchChanged (); + void headingChanged (); + void groundSpeedChanged (); + void airSpeedChanged (); + void climbRateChanged (); + void altitudeRelativeChanged(); + void altitudeWGS84Changed (); + void altitudeAMSLChanged (); + void latitudeChanged (); + void longitudeChanged (); + void mavPresentChanged (); + void batteryVoltageChanged (); + void batteryPercentChanged (); + void systemArmedChanged (); + void heartbeatTimeoutChanged(); + void currentModeChanged (); + void currentConfigChanged (); + void systemPixmapChanged (); + void satelliteCountChanged (); + void currentStateChanged (); + void systemNameChanged (); + void satelliteLockChanged (); + void waypointDistanceChanged(); + void currentWaypointChanged (); + void waypointsChanged (); + +private slots: + /** @brief Attitude from main autopilot / system state */ + void _updateAttitude (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp); + /** @brief Attitude from one specific component / redundant autopilot */ + void _updateAttitude (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp); + /** @brief Speed */ + void _updateSpeed (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp); + /** @brief Altitude */ + void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp); + void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError); + void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance); + void _forgetUAS (UASInterface* uas); + void _setActiveUAS (UASInterface* uas); + void _checkUpdate (); + void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); + void _updateArmingState (bool armed); + void _updateState (UASInterface* system, QString name, QString description); + void _updateMode (int system, QString name, QString description); + void _updateName (const QString& name); + void _setSystemType (UASInterface* uas, unsigned int systemType); + void _heartbeatTimeout (bool timeout, unsigned int ms); + void _updateCurrentWaypoint (quint16 id); + void _updateWaypointDistance (double distance); + void _setSatelliteCount (double val, QString name); + void _setSatLoc (UASInterface* uas, int fix); + void _updateWaypointViewOnly (int uas, Waypoint* wp); + void _waypointViewOnlyListChanged (); + +private: + bool _isAirplane (); + void _addChange (int id); + float _oneDecimal (float value); + +private: + UASInterface* _mav; + float _roll; + float _pitch; + float _heading; + float _altitudeAMSL; + float _altitudeWGS84; + float _altitudeRelative; + float _groundSpeed; + float _airSpeed; + float _climbRate; + float _navigationAltitudeError; + float _navigationSpeedError; + float _navigationCrosstrackError; + float _navigationTargetBearing; + float _latitude; + float _longitude; + QTimer* _refreshTimer; + QList _changes; + double _batteryVoltage; + double _batteryPercent; + bool _systemArmed; + QString _currentState; + QString _currentMode; + QString _systemName; + QString _systemPixmap; + unsigned int _currentHeartbeatTimeout; + double _waypointDistance; + quint16 _currentWaypoint; + int _satelliteCount; + int _satelliteLock; + UASWaypointManager* _wpm; + int _updateCount; + QList_waypoints; +}; + +#endif // MAVMANAGER_H diff --git a/src/QmlControls/QGCMavManager.cc b/src/QmlControls/QGCMavManager.cc deleted file mode 100644 index 6842713..0000000 --- a/src/QmlControls/QGCMavManager.cc +++ /dev/null @@ -1,626 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief QGC Mav Manager (QML Bindings) - * @author Gus Grubba - */ - -#include "MainWindow.h" -#include "UASManager.h" -#include "Waypoint.h" -#include "QGCMavManager.h" - -#define UPDATE_TIMER 50 -#define DEFAULT_LAT 38.965767f -#define DEFAULT_LON -120.083923f - -MavManager::MavManager(QObject *parent) - : QObject(parent) - , _mav(NULL) - , _roll(0.0f) - , _pitch(0.0f) - , _heading(0.0f) - , _altitudeAMSL(0.0f) - , _altitudeWGS84(0.0f) - , _altitudeRelative(0.0f) - , _groundSpeed(0.0f) - , _airSpeed(0.0f) - , _climbRate(0.0f) - , _navigationAltitudeError(0.0f) - , _navigationSpeedError(0.0f) - , _navigationCrosstrackError(0.0f) - , _navigationTargetBearing(0.0f) - , _latitude(DEFAULT_LAT) - , _longitude(DEFAULT_LON) - , _refreshTimer(new QTimer(this)) - , _batteryVoltage(0.0) - , _batteryPercent(0.0) - , _systemArmed(false) - , _currentHeartbeatTimeout(0) - , _waypointDistance(0.0) - , _currentWaypoint(0) - , _satelliteCount(-1) - , _satelliteLock(0) - , _wpm(NULL) - , _updateCount(0) -{ - // Connect with UAS signal - _setActiveUAS(UASManager::instance()->getActiveUAS()); - connect(UASManager::instance(), SIGNAL(UASDeleted(UASInterface*)), this, SLOT(_forgetUAS(UASInterface*))); - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(_setActiveUAS(UASInterface*))); - // Refresh timer - connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate())); - _refreshTimer->setInterval(UPDATE_TIMER); - _refreshTimer->start(UPDATE_TIMER); - emit heartbeatTimeoutChanged(); -} - -MavManager::~MavManager() -{ - _refreshTimer->stop(); -} - -void MavManager::saveSetting(const QString &name, const QString& value) -{ - QSettings settings; - settings.setValue(name, value); -} - -QString MavManager::loadSetting(const QString &name, const QString& defaultValue) -{ - QSettings settings; - return settings.value(name, defaultValue).toString(); -} - -void MavManager::_forgetUAS(UASInterface* uas) -{ - if (_mav != NULL && _mav == uas) { - // Disconnect any previously connected active MAV - disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); - disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); - disconnect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); - disconnect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); - disconnect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); - disconnect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString))); - disconnect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool))); - disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); - disconnect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); - disconnect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); - disconnect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); - disconnect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); - disconnect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); - disconnect(_mav, &UASInterface::localizationChanged, this, &MavManager::_setSatLoc); - if (_wpm) { - disconnect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &MavManager::_updateCurrentWaypoint); - disconnect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &MavManager::_updateWaypointDistance); - disconnect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); - disconnect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); - } - UAS* pUas = dynamic_cast(_mav); - if(pUas) { - disconnect(pUas, &UAS::satelliteCountChanged, this, &MavManager::_setSatelliteCount); - } - _mav = NULL; - _satelliteCount = -1; - emit mavPresentChanged(); - emit satelliteCountChanged(); - } -} - -void MavManager::_setActiveUAS(UASInterface* uas) -{ - if (uas == _mav) - return; - // Disconnect the previous one (if any) - if(_mav) { - _forgetUAS(_mav); - } - if (uas) { - // Reset satellite count (no GPS) - _satelliteCount = -1; - emit satelliteCountChanged(); - // Reset connection lost (if any) - _currentHeartbeatTimeout = 0; - emit heartbeatTimeoutChanged(); - // Set new UAS - _mav = uas; - // Now connect the new UAS - connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); - connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); - connect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); - connect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); - connect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); - connect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString))); - connect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool))); - connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); - connect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); - connect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); - connect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); - connect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); - connect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); - connect(_mav, &UASInterface::localizationChanged, this, &MavManager::_setSatLoc); - _wpm = _mav->getWaypointManager(); - if (_wpm) { - connect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &MavManager::_updateCurrentWaypoint); - connect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &MavManager::_updateWaypointDistance); - connect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); - connect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)),this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); - _wpm->readWaypoints(true); - } - UAS* pUas = dynamic_cast(_mav); - if(pUas) { - _setSatelliteCount(pUas->getSatelliteCount(), QString("")); - connect(pUas, &UAS::satelliteCountChanged, this, &MavManager::_setSatelliteCount); - } - _setSystemType(_mav, _mav->getSystemType()); - _updateArmingState(_mav->isArmed()); - } - emit mavPresentChanged(); -} - -void MavManager::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64) -{ - if (isinf(roll)) { - _roll = std::numeric_limits::quiet_NaN(); - } else { - float rolldeg = _oneDecimal(roll * (180.0 / M_PI)); - if (fabs(roll - rolldeg) > 1.0) { - _roll = rolldeg; - if(_refreshTimer->isActive()) { - emit rollChanged(); - } - } - if(_roll != rolldeg) { - _roll = rolldeg; - _addChange(ROLL_CHANGED); - } - } - if (isinf(pitch)) { - _pitch = std::numeric_limits::quiet_NaN(); - } else { - float pitchdeg = _oneDecimal(pitch * (180.0 / M_PI)); - if (fabs(pitch - pitchdeg) > 1.0) { - _pitch = pitchdeg; - if(_refreshTimer->isActive()) { - emit pitchChanged(); - } - } - if(_pitch != pitchdeg) { - _pitch = pitchdeg; - _addChange(PITCH_CHANGED); - } - } - if (isinf(yaw)) { - _heading = std::numeric_limits::quiet_NaN(); - } else { - yaw = _oneDecimal(yaw * (180.0 / M_PI)); - if (yaw < 0) yaw += 360; - if (fabs(_heading - yaw) > 1.0) { - _heading = yaw; - if(_refreshTimer->isActive()) { - emit headingChanged(); - } - } - if(_heading != yaw) { - _heading = yaw; - _addChange(HEADING_CHANGED); - } - } -} - -void MavManager::_updateAttitude(UASInterface* uas, int, double roll, double pitch, double yaw, quint64 timestamp) -{ - _updateAttitude(uas, roll, pitch, yaw, timestamp); -} - -void MavManager::_updateSpeed(UASInterface*, double groundSpeed, double airSpeed, quint64) -{ - groundSpeed = _oneDecimal(groundSpeed); - if (fabs(_groundSpeed - groundSpeed) > 0.5) { - _groundSpeed = groundSpeed; - if(_refreshTimer->isActive()) { - emit groundSpeedChanged(); - } - } - airSpeed = _oneDecimal(airSpeed); - if (fabs(_airSpeed - airSpeed) > 1.0) { - _airSpeed = airSpeed; - if(_refreshTimer->isActive()) { - emit airSpeedChanged(); - } - } - if(_groundSpeed != groundSpeed) { - _groundSpeed = groundSpeed; - _addChange(GROUNDSPEED_CHANGED); - } - if(_airSpeed != airSpeed) { - _airSpeed = airSpeed; - _addChange(AIRSPEED_CHANGED); - } -} - -void MavManager::_updateAltitude(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64) { - altitudeAMSL = _oneDecimal(altitudeAMSL); - if (fabs(_altitudeAMSL - altitudeAMSL) > 0.5) { - _altitudeAMSL = altitudeAMSL; - if(_refreshTimer->isActive()) { - emit altitudeAMSLChanged(); - } - } - altitudeWGS84 = _oneDecimal(altitudeWGS84); - if (fabs(_altitudeWGS84 - altitudeWGS84) > 0.5) { - _altitudeWGS84 = altitudeWGS84; - if(_refreshTimer->isActive()) { - emit altitudeWGS84Changed(); - } - } - altitudeRelative = _oneDecimal(altitudeRelative); - if (fabs(_altitudeRelative - altitudeRelative) > 0.5) { - _altitudeRelative = altitudeRelative; - if(_refreshTimer->isActive()) { - emit altitudeRelativeChanged(); - } - } - climbRate = _oneDecimal(climbRate); - if (fabs(_climbRate - climbRate) > 0.5) { - _climbRate = climbRate; - if(_refreshTimer->isActive()) { - emit climbRateChanged(); - } - } - if(_altitudeAMSL != altitudeAMSL) { - _altitudeAMSL = altitudeAMSL; - _addChange(ALTITUDEAMSL_CHANGED); - } - if(_altitudeWGS84 != altitudeWGS84) { - _altitudeWGS84 = altitudeWGS84; - _addChange(ALTITUDEWGS84_CHANGED); - } - if(_altitudeRelative != altitudeRelative) { - _altitudeRelative = altitudeRelative; - _addChange(ALTITUDERELATIVE_CHANGED); - } - if(_climbRate != climbRate) { - _climbRate = climbRate; - _addChange(CLIMBRATE_CHANGED); - } -} - -void MavManager::_updateNavigationControllerErrors(UASInterface*, double altitudeError, double speedError, double xtrackError) { - _navigationAltitudeError = altitudeError; - _navigationSpeedError = speedError; - _navigationCrosstrackError = xtrackError; -} - -void MavManager::_updateNavigationControllerData(UASInterface *uas, float, float, float, float targetBearing, float) { - if (_mav == uas) { - _navigationTargetBearing = targetBearing; - } -} - -/* - * Internal - */ - -bool MavManager::_isAirplane() { - if (_mav) - return _mav->isAirplane(); - return false; -} - -void MavManager::_addChange(int id) -{ - if(!_changes.contains(id)) { - _changes.append(id); - } -} - -float MavManager::_oneDecimal(float value) -{ - int i = (value * 10); - return (float)i / 10.0; -} - -void MavManager::_checkUpdate() -{ - // Update current location - if(_mav) { - if(_latitude != _mav->getLatitude()) { - _latitude = _mav->getLatitude(); - emit latitudeChanged(); - } - if(_longitude != _mav->getLongitude()) { - _longitude = _mav->getLongitude(); - emit longitudeChanged(); - } - } - // The timer rate is 20Hz for the coordinates above. These below we only check - // twice a second. - if(++_updateCount > 9) { - _updateCount = 0; - // Check for changes - // Significant changes, that is, whole number changes, are updated immediatelly. - // For every message however, we set a flag for what changed and this timer updates - // them to bring everything up-to-date. This prevents an avalanche of UI updates. - foreach(int i, _changes) { - switch (i) { - case ROLL_CHANGED: - emit rollChanged(); - break; - case PITCH_CHANGED: - emit pitchChanged(); - break; - case HEADING_CHANGED: - emit headingChanged(); - break; - case GROUNDSPEED_CHANGED: - emit groundSpeedChanged(); - break; - case AIRSPEED_CHANGED: - emit airSpeedChanged(); - break; - case CLIMBRATE_CHANGED: - emit climbRateChanged(); - break; - case ALTITUDERELATIVE_CHANGED: - emit altitudeRelativeChanged(); - break; - case ALTITUDEWGS84_CHANGED: - emit altitudeWGS84Changed(); - break; - case ALTITUDEAMSL_CHANGED: - emit altitudeAMSLChanged(); - break; - default: - break; - } - } - _changes.clear(); - } -} - -QString MavManager::getMavIconColor() -{ - // TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette - if(_mav) - return _mav->getColor().name(); - else - return QString("black"); -} - -void MavManager::_updateArmingState(bool armed) -{ - if(_systemArmed != armed) { - _systemArmed = armed; - emit systemArmedChanged(); - } -} - -void MavManager::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int) -{ - - if(percent < 0.0) { - percent = 0.0; - } - if(voltage < 0.0) { - voltage = 0.0; - } - if (_batteryVoltage != voltage) { - _batteryVoltage = voltage; - emit batteryVoltageChanged(); - } - if (_batteryPercent != percent) { - _batteryPercent = percent; - emit batteryPercentChanged(); - } -} - -void MavManager::_updateState(UASInterface*, QString name, QString) -{ - if (_currentState != name) { - _currentState = name; - emit currentStateChanged(); - } -} - -void MavManager::_updateMode(int, QString name, QString) -{ - if (name.size()) { - QString shortMode = name; - shortMode = shortMode.replace("D|", ""); - shortMode = shortMode.replace("A|", ""); - if (_currentMode != shortMode) { - _currentMode = shortMode; - emit currentModeChanged(); - } - } -} - -void MavManager::_updateName(const QString& name) -{ - if (_systemName != name) { - _systemName = name; - emit systemNameChanged(); - } -} - -/** - * The current system type is represented through the system icon. - * - * @param uas Source system, has to be the same as this->uas - * @param systemType type ID, following the MAVLink system type conventions - * @see http://pixhawk.ethz.ch/software/mavlink - */ -void MavManager::_setSystemType(UASInterface*, unsigned int systemType) -{ - _systemPixmap = "qrc:/res/mavs/"; - switch (systemType) { - case MAV_TYPE_GENERIC: - _systemPixmap += "Generic"; - break; - case MAV_TYPE_FIXED_WING: - _systemPixmap += "FixedWing"; - break; - case MAV_TYPE_QUADROTOR: - _systemPixmap += "QuadRotor"; - break; - case MAV_TYPE_COAXIAL: - _systemPixmap += "Coaxial"; - break; - case MAV_TYPE_HELICOPTER: - _systemPixmap += "Helicopter"; - break; - case MAV_TYPE_ANTENNA_TRACKER: - _systemPixmap += "AntennaTracker"; - break; - case MAV_TYPE_GCS: - _systemPixmap += "Groundstation"; - break; - case MAV_TYPE_AIRSHIP: - _systemPixmap += "Airship"; - break; - case MAV_TYPE_FREE_BALLOON: - _systemPixmap += "FreeBalloon"; - break; - case MAV_TYPE_ROCKET: - _systemPixmap += "Rocket"; - break; - case MAV_TYPE_GROUND_ROVER: - _systemPixmap += "GroundRover"; - break; - case MAV_TYPE_SURFACE_BOAT: - _systemPixmap += "SurfaceBoat"; - break; - case MAV_TYPE_SUBMARINE: - _systemPixmap += "Submarine"; - break; - case MAV_TYPE_HEXAROTOR: - _systemPixmap += "HexaRotor"; - break; - case MAV_TYPE_OCTOROTOR: - _systemPixmap += "OctoRotor"; - break; - case MAV_TYPE_TRICOPTER: - _systemPixmap += "TriCopter"; - break; - case MAV_TYPE_FLAPPING_WING: - _systemPixmap += "FlappingWing"; - break; - case MAV_TYPE_KITE: - _systemPixmap += "Kite"; - break; - default: - _systemPixmap += "Unknown"; - break; - } - emit systemPixmapChanged(); -} - -void MavManager::_heartbeatTimeout(bool timeout, unsigned int ms) -{ - unsigned int elapsed = ms; - if (!timeout) - { - elapsed = 0; - } - if(elapsed != _currentHeartbeatTimeout) { - _currentHeartbeatTimeout = elapsed; - emit heartbeatTimeoutChanged(); - } -} - -void MavManager::_setSatelliteCount(double val, QString) -{ - // I'm assuming that a negative value or over 99 means there is no GPS - if(val < 0.0) val = -1.0; - if(val > 99.0) val = -1.0; - if(_satelliteCount != (int)val) { - _satelliteCount = (int)val; - emit satelliteCountChanged(); - } -} - -void MavManager::_setSatLoc(UASInterface*, int fix) -{ - // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock - if(_satelliteLock != fix) { - _satelliteLock = fix; - emit satelliteLockChanged(); - } -} - -void MavManager::_updateWaypointDistance(double distance) -{ - if (_waypointDistance != distance) { - _waypointDistance = distance; - emit waypointDistanceChanged(); - } -} - -void MavManager::_updateCurrentWaypoint(quint16 id) -{ - if (_currentWaypoint != id) { - _currentWaypoint = id; - emit currentWaypointChanged(); - } -} - -void MavManager::_updateWaypointViewOnly(int, Waypoint* /*wp*/) -{ - /* - bool changed = false; - for(int i = 0; i < _waypoints.count(); i++) { - if(_waypoints[i].getId() == wp->getId()) { - _waypoints[i] = *wp; - changed = true; - break; - } - } - if(changed) { - emit waypointListChanged(); - } - */ -} - -void MavManager::_waypointViewOnlyListChanged() -{ - if(_wpm) { - const QList &waypoints = _wpm->getWaypointViewOnlyList(); - _waypoints.clear(); - for(int i = 0; i < waypoints.count(); i++) { - Waypoint* wp = waypoints[i]; - _waypoints.append(new Waypoint(*wp)); - } - emit waypointsChanged(); - /* - if(_longitude == DEFAULT_LON && _latitude == DEFAULT_LAT && _waypoints.length()) { - _longitude = _waypoints[0]->getLongitude(); - _latitude = _waypoints[0]->getLatitude(); - emit longitudeChanged(); - emit latitudeChanged(); - } - */ - } -} diff --git a/src/QmlControls/QGCMavManager.h b/src/QmlControls/QGCMavManager.h deleted file mode 100644 index 56b25a3..0000000 --- a/src/QmlControls/QGCMavManager.h +++ /dev/null @@ -1,215 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief QGC Mav Manager (QML Bindings) - * @author Gus Grubba - */ - -#ifndef MAVMANAGER_H -#define MAVMANAGER_H - -#include -#include -#include -#include "Waypoint.h" - -class UASInterface; -class UASWaypointManager; - -class MavManager : public QObject -{ - Q_OBJECT - Q_ENUMS(MessageType_t) -public: - explicit MavManager(QObject *parent = 0); - ~MavManager(); - - enum { - ROLL_CHANGED, - PITCH_CHANGED, - HEADING_CHANGED, - GROUNDSPEED_CHANGED, - AIRSPEED_CHANGED, - CLIMBRATE_CHANGED, - ALTITUDERELATIVE_CHANGED, - ALTITUDEWGS84_CHANGED, - ALTITUDEAMSL_CHANGED - }; - - Q_INVOKABLE QString getMavIconColor(); - Q_INVOKABLE void saveSetting (const QString &key, const QString& value); - Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); - - Q_PROPERTY(float roll READ roll NOTIFY rollChanged) - Q_PROPERTY(float pitch READ pitch NOTIFY pitchChanged) - Q_PROPERTY(float heading READ heading NOTIFY headingChanged) - Q_PROPERTY(float groundSpeed READ groundSpeed NOTIFY groundSpeedChanged) - Q_PROPERTY(float airSpeed READ airSpeed NOTIFY airSpeedChanged) - Q_PROPERTY(float climbRate READ climbRate NOTIFY climbRateChanged) - Q_PROPERTY(float altitudeRelative READ altitudeRelative NOTIFY altitudeRelativeChanged) - Q_PROPERTY(float altitudeWGS84 READ altitudeWGS84 NOTIFY altitudeWGS84Changed) - Q_PROPERTY(float altitudeAMSL READ altitudeAMSL NOTIFY altitudeAMSLChanged) - Q_PROPERTY(float latitude READ latitude NOTIFY latitudeChanged) - Q_PROPERTY(float longitude READ longitude NOTIFY longitudeChanged) - Q_PROPERTY(bool mavPresent READ mavPresent NOTIFY mavPresentChanged) - Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) - Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) - Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged) - Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged) - Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged) - Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged) - Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) - Q_PROPERTY(QString systemName READ systemName NOTIFY systemNameChanged) - Q_PROPERTY(int satelliteLock READ satelliteLock NOTIFY satelliteLockChanged) - Q_PROPERTY(double waypointDistance READ waypointDistance NOTIFY waypointDistanceChanged) - Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged) - Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) - Q_PROPERTY(QQmlListProperty waypoints READ waypoints NOTIFY waypointsChanged) - - float roll () { return _roll; } - float pitch () { return _pitch; } - float heading () { return _heading; } - float groundSpeed () { return _groundSpeed; } - float airSpeed () { return _airSpeed; } - float climbRate () { return _climbRate; } - float altitudeRelative () { return _altitudeRelative; } - float altitudeWGS84 () { return _altitudeWGS84; } - float altitudeAMSL () { return _altitudeAMSL; } - float latitude () { return _latitude; } - float longitude () { return _longitude; } - bool mavPresent () { return _mav != NULL; } - int satelliteCount () { return _satelliteCount; } - double batteryVoltage () { return _batteryVoltage; } - double batteryPercent () { return _batteryPercent; } - bool systemArmed () { return _systemArmed; } - QString currentMode () { return _currentMode; } - QString systemPixmap () { return _systemPixmap; } - QString currentState () { return _currentState; } - QString systemName () { return _systemName; } - int satelliteLock () { return _satelliteLock; } - double waypointDistance () { return _waypointDistance; } - uint16_t currentWaypoint () { return _currentWaypoint; } - unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } - - QQmlListProperty waypoints() {return QQmlListProperty(this, _waypoints); } - -signals: - void rollChanged (); - void pitchChanged (); - void headingChanged (); - void groundSpeedChanged (); - void airSpeedChanged (); - void climbRateChanged (); - void altitudeRelativeChanged(); - void altitudeWGS84Changed (); - void altitudeAMSLChanged (); - void latitudeChanged (); - void longitudeChanged (); - void mavPresentChanged (); - void batteryVoltageChanged (); - void batteryPercentChanged (); - void systemArmedChanged (); - void heartbeatTimeoutChanged(); - void currentModeChanged (); - void currentConfigChanged (); - void systemPixmapChanged (); - void satelliteCountChanged (); - void currentStateChanged (); - void systemNameChanged (); - void satelliteLockChanged (); - void waypointDistanceChanged(); - void currentWaypointChanged (); - void waypointsChanged (); - -private slots: - /** @brief Attitude from main autopilot / system state */ - void _updateAttitude (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp); - /** @brief Attitude from one specific component / redundant autopilot */ - void _updateAttitude (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp); - /** @brief Speed */ - void _updateSpeed (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp); - /** @brief Altitude */ - void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp); - void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError); - void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance); - void _forgetUAS (UASInterface* uas); - void _setActiveUAS (UASInterface* uas); - void _checkUpdate (); - void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); - void _updateArmingState (bool armed); - void _updateState (UASInterface* system, QString name, QString description); - void _updateMode (int system, QString name, QString description); - void _updateName (const QString& name); - void _setSystemType (UASInterface* uas, unsigned int systemType); - void _heartbeatTimeout (bool timeout, unsigned int ms); - void _updateCurrentWaypoint (quint16 id); - void _updateWaypointDistance (double distance); - void _setSatelliteCount (double val, QString name); - void _setSatLoc (UASInterface* uas, int fix); - void _updateWaypointViewOnly (int uas, Waypoint* wp); - void _waypointViewOnlyListChanged (); - -private: - bool _isAirplane (); - void _addChange (int id); - float _oneDecimal (float value); - -private: - UASInterface* _mav; - float _roll; - float _pitch; - float _heading; - float _altitudeAMSL; - float _altitudeWGS84; - float _altitudeRelative; - float _groundSpeed; - float _airSpeed; - float _climbRate; - float _navigationAltitudeError; - float _navigationSpeedError; - float _navigationCrosstrackError; - float _navigationTargetBearing; - float _latitude; - float _longitude; - QTimer* _refreshTimer; - QList _changes; - double _batteryVoltage; - double _batteryPercent; - bool _systemArmed; - QString _currentState; - QString _currentMode; - QString _systemName; - QString _systemPixmap; - unsigned int _currentHeartbeatTimeout; - double _waypointDistance; - quint16 _currentWaypoint; - int _satelliteCount; - int _satelliteLock; - UASWaypointManager* _wpm; - int _updateCount; - QList_waypoints; -}; - -#endif // MAVMANAGER_H diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index fde97c8..f93546b 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -60,7 +60,7 @@ This file is part of the QGROUNDCONTROL project #include "Linecharts.h" #include "QGCTabbedInfoView.h" #include "UASRawStatusView.h" -#include "QGCFlightDisplay.h" +#include "FlightDisplay.h" #include "SetupView.h" #include "SerialSettingsDialog.h" #include "terminalconsole.h" @@ -474,7 +474,7 @@ void MainWindow::_buildExperimentalPlanView(void) void MainWindow::_buildFlightView(void) { if (!_flightView) { - _flightView = new QGCFlightDisplay(this); + _flightView = new FlightDisplay(this); _flightView->setVisible(false); } } @@ -579,7 +579,7 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) widget = hddisplay; } else if (widgetName == _pfdDockWidgetName) { - widget = new QGCFlightDisplay(this); + widget = new FlightDisplay(this); } else if (widgetName == _hudDockWidgetName) { widget = new HUD(320,240,this); } else if (widgetName == _uasInfoViewDockWidgetName) { diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index e3c0f86..d350fda 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -61,7 +61,7 @@ This file is part of the QGROUNDCONTROL project #include "MainToolBar.h" #include "LogCompressor.h" -#include "QGCFlightDisplay.h" +#include "FlightDisplay.h" #include "QGCMAVLinkInspector.h" #include "QGCMAVLinkLogPlayer.h" #include "MAVLinkDecoder.h" @@ -76,7 +76,7 @@ class QGCStatusBar; class Linecharts; class QGCDataPlot2D; class QGCUASFileViewMulti; -class QGCFlightDisplay; +class FlightDisplay; /** * @brief Main Application Window @@ -128,7 +128,7 @@ public: MainToolBar* getMainToolBar(void) { return _mainToolBar; } /// @brief Gets a pointer to the Main Flight Display - QGCFlightDisplay* getFlightDisplay() { return dynamic_cast(_flightView.data()); } + FlightDisplay* getFlightDisplay() { return dynamic_cast(_flightView.data()); } QWidget* getCurrentViewWidget(void) { return _currentViewWidget; } diff --git a/src/ui/flightdisplay/FlightDisplay.cc b/src/ui/flightdisplay/FlightDisplay.cc new file mode 100644 index 0000000..7ba501f --- /dev/null +++ b/src/ui/flightdisplay/FlightDisplay.cc @@ -0,0 +1,77 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2015 QGROUNDCONTROL PROJECT + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * @brief QGC Main Flight Display + * @author Gus Grubba + */ + +#include +#include +#include + +#include "MainWindow.h" +#include "FlightDisplay.h" +#include "UASManager.h" + +const char* kMainFlightDisplayGroup = "MainFlightDisplay"; + +FlightDisplay::FlightDisplay(QWidget *parent) + : QGCQmlWidgetHolder(parent) +{ + setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); + setObjectName("MainFlightDisplay"); + // Get rid of layout default margins + QLayout* pl = layout(); + if(pl) { + pl->setContentsMargins(0,0,0,0); + } +#ifndef __android__ + setMinimumWidth( 380 * MainWindow::pixelSizeFactor()); + setMinimumHeight(400 * MainWindow::pixelSizeFactor()); +#endif + setContextPropertyObject("flightDisplay", this); + setSource(QUrl::fromUserInput("qrc:/qml/FlightDisplay.qml")); + setVisible(true); +} + +FlightDisplay::~FlightDisplay() +{ +} + +void FlightDisplay::saveSetting(const QString &name, const QString& value) +{ + QSettings settings; + QString key(kMainFlightDisplayGroup); + key += "/" + name; + settings.setValue(key, value); +} + +QString FlightDisplay::loadSetting(const QString &name, const QString& defaultValue) +{ + QSettings settings; + QString key(kMainFlightDisplayGroup); + key += "/" + name; + return settings.value(key, defaultValue).toString(); +} diff --git a/src/ui/flightdisplay/FlightDisplay.h b/src/ui/flightdisplay/FlightDisplay.h new file mode 100644 index 0000000..ba374c2 --- /dev/null +++ b/src/ui/flightdisplay/FlightDisplay.h @@ -0,0 +1,55 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2015 QGROUNDCONTROL PROJECT + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * @brief QGC Main Flight Display + * @author Gus Grubba + */ + +#ifndef QGCFLIGHTDISPLAY_H +#define QGCFLIGHTDISPLAY_H + +#include "QGCQmlWidgetHolder.h" + +class UASInterface; + +class FlightDisplay : public QGCQmlWidgetHolder +{ + Q_OBJECT +public: + FlightDisplay(QWidget* parent = NULL); + ~FlightDisplay(); + + /// @brief Invokes the Flight Display Options menu + void showOptionsMenu() { emit showOptionsMenuChanged(); } + + Q_INVOKABLE void saveSetting (const QString &key, const QString& value); + Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); + +signals: + void showOptionsMenuChanged (); + +}; + +#endif // QGCFLIGHTDISPLAY_H diff --git a/src/ui/flightdisplay/QGCFlightDisplay.cc b/src/ui/flightdisplay/QGCFlightDisplay.cc deleted file mode 100644 index cd480c5..0000000 --- a/src/ui/flightdisplay/QGCFlightDisplay.cc +++ /dev/null @@ -1,77 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief QGC Main Flight Display - * @author Gus Grubba - */ - -#include -#include -#include - -#include "MainWindow.h" -#include "QGCFlightDisplay.h" -#include "UASManager.h" - -const char* kMainFlightDisplayGroup = "MainFlightDisplay"; - -QGCFlightDisplay::QGCFlightDisplay(QWidget *parent) - : QGCQmlWidgetHolder(parent) -{ - setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); - setObjectName("MainFlightDisplay"); - // Get rid of layout default margins - QLayout* pl = layout(); - if(pl) { - pl->setContentsMargins(0,0,0,0); - } -#ifndef __android__ - setMinimumWidth( 380 * MainWindow::pixelSizeFactor()); - setMinimumHeight(400 * MainWindow::pixelSizeFactor()); -#endif - setContextPropertyObject("flightDisplay", this); - setSource(QUrl::fromUserInput("qrc:/qml/FlightDisplay.qml")); - setVisible(true); -} - -QGCFlightDisplay::~QGCFlightDisplay() -{ -} - -void QGCFlightDisplay::saveSetting(const QString &name, const QString& value) -{ - QSettings settings; - QString key(kMainFlightDisplayGroup); - key += "/" + name; - settings.setValue(key, value); -} - -QString QGCFlightDisplay::loadSetting(const QString &name, const QString& defaultValue) -{ - QSettings settings; - QString key(kMainFlightDisplayGroup); - key += "/" + name; - return settings.value(key, defaultValue).toString(); -} diff --git a/src/ui/flightdisplay/QGCFlightDisplay.h b/src/ui/flightdisplay/QGCFlightDisplay.h deleted file mode 100644 index 07f069b..0000000 --- a/src/ui/flightdisplay/QGCFlightDisplay.h +++ /dev/null @@ -1,55 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief QGC Main Flight Display - * @author Gus Grubba - */ - -#ifndef QGCFLIGHTDISPLAY_H -#define QGCFLIGHTDISPLAY_H - -#include "QGCQmlWidgetHolder.h" - -class UASInterface; - -class QGCFlightDisplay : public QGCQmlWidgetHolder -{ - Q_OBJECT -public: - QGCFlightDisplay(QWidget* parent = NULL); - ~QGCFlightDisplay(); - - /// @brief Invokes the Flight Display Options menu - void showOptionsMenu() { emit showOptionsMenuChanged(); } - - Q_INVOKABLE void saveSetting (const QString &key, const QString& value); - Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); - -signals: - void showOptionsMenuChanged (); - -}; - -#endif // QGCFLIGHTDISPLAY_H diff --git a/src/ui/toolbar/MainToolBar.cc b/src/ui/toolbar/MainToolBar.cc index 9fcc54f..470cd8a 100644 --- a/src/ui/toolbar/MainToolBar.cc +++ b/src/ui/toolbar/MainToolBar.cc @@ -34,7 +34,7 @@ This file is part of the QGROUNDCONTROL project #include "MainWindow.h" #include "UASMessageHandler.h" #include "UASMessageView.h" -#include "QGCFlightDisplay.h" +#include "FlightDisplay.h" MainToolBar::MainToolBar(QWidget* parent) : QGCQmlWidgetHolder(parent) @@ -150,7 +150,7 @@ void MainToolBar::onFlyView() void MainToolBar::onFlyViewMenu() { - QGCFlightDisplay* fdsp = MainWindow::instance()->getFlightDisplay(); + FlightDisplay* fdsp = MainWindow::instance()->getFlightDisplay(); if(fdsp) { fdsp->showOptionsMenu(); }