diff --git a/.travis.yml b/.travis.yml index 16f60e65da8aaa8c4063ff373065e05c80c83b0f..d7d9db68e497b04632330a487a10a8bf0ea4b596 100644 --- a/.travis.yml +++ b/.travis.yml @@ -17,12 +17,9 @@ matrix: - os: linux env: SPEC=linux-g++-64 CONFIG=installer sudo: false - - os: linux - env: CONFIG=doxygen - sudo: false - os: osx osx_image: xcode7 - env: SPEC=macx-clang CONFIG=debug + env: SPEC=macx-clang CONFIG=debug QT_FATAL_WARNINGS=1 - os: osx osx_image: xcode7 env: SPEC=macx-clang CONFIG=installer @@ -34,6 +31,9 @@ matrix: language: android env: SPEC=android-g++ CONFIG=installer sudo: false + - os: linux + env: CONFIG=doxygen + sudo: false android: components: @@ -111,6 +111,7 @@ before_script: - if [ "${CONFIG}" != "doxygen" ]; then qmake -r qgroundcontrol.pro CONFIG+=${CONFIG} CONFIG+=WarningsAsErrorsOn -spec ${SPEC}; fi script: + - ./tools/update_android_version.sh - echo 'Building QGroundControl' && echo -en 'travis_fold:start:script.1\\r' - if [ "${CONFIG}" != "doxygen" ]; then make -j4; fi - if [ "${CONFIG}" = "doxygen" ]; then cd src && doxygen documentation.dox; fi @@ -118,6 +119,14 @@ script: - if [[ "${TRAVIS_OS_NAME}" = "linux" && "${CONFIG}" = "debug" ]]; then ./debug/qgroundcontrol --unittest; fi - if [[ "${TRAVIS_OS_NAME}" = "osx" && "${CONFIG}" = "debug" ]]; then ./debug/qgroundcontrol.app/Contents/MacOS/qgroundcontrol --unittest; fi +after_success: + - if [[ "${TRAVIS_OS_NAME}" = "android" && "${TRAVIS_PULL_REQUEST}" = "false" && "${TRAVIS_BRANCH}" = "master" ]]; then + pip install --user google-api-python-client PyOpenSSL + && openssl aes-256-cbc -K $encrypted_25db6eb7c3fd_key -iv $encrypted_25db6eb7c3fd_iv -in Google_Play_Android_Developer-bb93ae7d61ca.p12.enc -out android/Google_Play_Android_Developer-bb93ae7d61ca.p12 -d + && ./tools/google_play_upload.py org.mavlink.qgroundcontrol release/package/qgroundcontrol.apk + ; + fi + deploy: - provider: s3 access_key_id: AKIAIVORNALE7NHD3T6Q diff --git a/Google_Play_Android_Developer-bb93ae7d61ca.p12.enc b/Google_Play_Android_Developer-bb93ae7d61ca.p12.enc new file mode 100644 index 0000000000000000000000000000000000000000..b821f735f95a0d563a0578725eb52b8ce2f99e29 Binary files /dev/null and b/Google_Play_Android_Developer-bb93ae7d61ca.p12.enc differ diff --git a/QGCApplication.pro b/QGCApplication.pro index 69baf0944632681a9774883286af9d2d5bc9061e..3ec9e9cab0c961cd0a29010f4fa642645dc7c465 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -200,7 +200,6 @@ FORMS += \ src/ui/uas/UASQuickView.ui \ src/ui/uas/UASQuickViewItemSelect.ui \ src/ui/UASInfo.ui \ - src/ui/UASRawStatusView.ui \ } HEADERS += \ @@ -240,7 +239,6 @@ HEADERS += \ src/QGCPalette.h \ src/QGCQmlWidgetHolder.h \ src/QGCQuickWidget.h \ - src/QGCSingleton.h \ src/QGCTemporaryFile.h \ src/QGCToolbox.h \ src/QmlControls/CoordinateVector.h \ @@ -317,7 +315,6 @@ HEADERS += \ src/ui/uas/UASQuickViewItem.h \ src/ui/uas/UASQuickViewItemSelect.h \ src/ui/uas/UASQuickViewTextItem.h \ - src/ui/UASRawStatusView.h \ src/VehicleSetup/JoystickConfigController.h \ src/ViewWidgets/CustomCommandWidget.h \ src/ViewWidgets/CustomCommandWidgetController.h \ @@ -355,7 +352,6 @@ SOURCES += \ src/QGCPalette.cc \ src/QGCQmlWidgetHolder.cpp \ src/QGCQuickWidget.cc \ - src/QGCSingleton.cc \ src/QGCTemporaryFile.cc \ src/QGCToolbox.cc \ src/QGCGeo.cc \ @@ -423,7 +419,6 @@ SOURCES += \ src/ui/uas/UASQuickViewItem.cc \ src/ui/uas/UASQuickViewItemSelect.cc \ src/ui/uas/UASQuickViewTextItem.cc \ - src/ui/UASRawStatusView.cpp \ src/VehicleSetup/JoystickConfigController.cc \ src/ViewWidgets/CustomCommandWidget.cc \ src/ViewWidgets/CustomCommandWidgetController.cc \ diff --git a/README.md b/README.md index 82b019415234b1544e3947c5d2e8c6adbb1a818d..4b023ae2d25ec9d41a0f255060f79553cbdb6397 100644 --- a/README.md +++ b/README.md @@ -20,12 +20,9 @@ ## Obtaining source code Source code for QGroundControl is kept on GitHub: https://github.com/mavlink/qgroundcontrol. ``` -git clone https://github.com/mavlink/qgroundcontrol.git -cd qgroundcontrol -git submodule init -git submodule update +git clone --recursive https://github.com/mavlink/qgroundcontrol.git ``` -Each time you pull new source to your repository you should re-run "git submodule update" to get the latest submodules as well. +Each time you pull new source to your repository you should run `git submodule update` to get the latest submodules as well. ### Supported Builds QGroundControl builds are supported for OSX, Linux, Windows and Android. QGroundControl uses [Qt](http://www.qt.io) as it's cross-platform support library and uses [QtCreator](http://doc.qt.io/qtcreator/index.html) as it's default build environment. diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index 6b503613c92fc568dd42382d089ed71f1baf41cc..0fbc93c95d431fcf3b41ef3abf3ab7cc8eb8706b 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -1,5 +1,5 @@ - + @@ -48,7 +48,7 @@ - + diff --git a/android/Google_Play_Android_Developer-bb93ae7d61ca.p12.enc b/android/Google_Play_Android_Developer-bb93ae7d61ca.p12.enc new file mode 100644 index 0000000000000000000000000000000000000000..22c154d6fb4ad72b63667f87fba1aaf88b4e674a Binary files /dev/null and b/android/Google_Play_Android_Developer-bb93ae7d61ca.p12.enc differ diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc index 7519398a743247fdea06372c4ca71bf7bb3aa3d8..468baf03c238843664ebccd06d84a46215c1f0ce 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc @@ -27,8 +27,8 @@ #include "APMAirframeComponent.h" #include "QGCQmlWidgetHolder.h" -APMAirframeComponent::APMAirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - APMComponent(uas, autopilot, parent), +APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + APMComponent(vehicle, autopilot, parent), _name(tr("Airframe")) { diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.h b/src/AutoPilotPlugins/APM/APMAirframeComponent.h index 4a763c66e12b7ef1a2bec80ea0a375134d44499a..4231af7cc0c7478c813bc9f187a6282540539af2 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.h +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.h @@ -31,7 +31,7 @@ class APMAirframeComponent : public APMComponent Q_OBJECT public: - APMAirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from APMComponent virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index ad623ca5bd81b491fa1006d49de9f7da696d767e..d79966a96a6a12988733b4fca626e72d022da5b0 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -48,7 +48,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) Q_ASSERT(_vehicle); if (parametersReady()) { - _airframeComponent = new APMAirframeComponent(_vehicle->uas(), this); + _airframeComponent = new APMAirframeComponent(_vehicle, this); Q_CHECK_PTR(_airframeComponent); _airframeComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); diff --git a/src/AutoPilotPlugins/APM/APMComponent.cc b/src/AutoPilotPlugins/APM/APMComponent.cc index 2a0b652fe194cfbeffbcf3f880b2235ef22fa09b..ec3cbf9b6e91fe989b8c5c8fb445cd5698274479 100644 --- a/src/AutoPilotPlugins/APM/APMComponent.cc +++ b/src/AutoPilotPlugins/APM/APMComponent.cc @@ -28,10 +28,10 @@ #include "Fact.h" #include "AutoPilotPlugin.h" -APMComponent::APMComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - VehicleComponent(uas, autopilot, parent) +APMComponent::APMComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + VehicleComponent(vehicle, autopilot, parent) { - Q_ASSERT(uas); + Q_ASSERT(vehicle); Q_ASSERT(autopilot); } diff --git a/src/AutoPilotPlugins/APM/APMComponent.h b/src/AutoPilotPlugins/APM/APMComponent.h index 88097c18a01c39dddae69de23d4dcf81070eb579..558c8d99f3f3f95fdefa6c76bf4243860f96cdb9 100644 --- a/src/AutoPilotPlugins/APM/APMComponent.h +++ b/src/AutoPilotPlugins/APM/APMComponent.h @@ -37,7 +37,7 @@ class APMComponent : public VehicleComponent Q_OBJECT public: - APMComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + APMComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); /// @brief Returns an list of parameter names for which a change should cause the setupCompleteChanged /// signal to be emitted. Last element is signalled by NULL. diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 08d7a5d27c7f6ce32a55bd579089de235a8689f4..1878ca9bd7302381c23b42ab714a46226d34fa69 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -170,7 +170,7 @@ const QMap >& AutoPilotPlugin::getGroupMap(void) void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) { - _vehicle->getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName()); + _vehicle->getParameterLoader()->writeParametersToStream(stream); } QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.cc b/src/AutoPilotPlugins/PX4/AirframeComponent.cc index f24e4fce1c153a2eb679c4d2064d1d489f3fb0d0..e99236ee2d2f214b0b975d2cc3cbe5361ac7834a 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.cc @@ -68,8 +68,8 @@ static const struct mavType mavTypeInfo[] = { static size_t cMavTypes = sizeof(mavTypeInfo) / sizeof(mavTypeInfo[0]); #endif -AirframeComponent::AirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - PX4Component(uas, autopilot, parent), +AirframeComponent::AirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + PX4Component(vehicle, autopilot, parent), _name(tr("Airframe")) { #if 0 diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.h b/src/AutoPilotPlugins/PX4/AirframeComponent.h index 8c02eb4cb2494c11bc537a80b5358b0d82cfffa5..b43d5907bec7303fd7952294d78a720fcaa4590d 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.h +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.h @@ -35,7 +35,7 @@ class AirframeComponent : public PX4Component Q_OBJECT public: - AirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + AirframeComponent(Vehicle* vehicles, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from PX4Component virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc index 6eac6335e002e8e1df2870d5ef3b380dbc8ae1ca..cef48ab81755faee245cd54cd53aae4e24726501 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc @@ -43,8 +43,8 @@ static const SwitchListItem switchList[] = { }; static const size_t cSwitchList = sizeof(switchList) / sizeof(switchList[0]); -FlightModesComponent::FlightModesComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - PX4Component(uas, autopilot, parent), +FlightModesComponent::FlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + PX4Component(vehicle, autopilot, parent), _name(tr("Flight Modes")) { } diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.h b/src/AutoPilotPlugins/PX4/FlightModesComponent.h index 19e772f82013473e000f3fef8fcd83d56c4e6f8e..e5a3adcf464bc8947b68fd3aaf6d1f075eb0bc2e 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.h +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.h @@ -35,7 +35,7 @@ class FlightModesComponent : public PX4Component Q_OBJECT public: - FlightModesComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + FlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from PX4Component virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc index 5fa55e4e44cc28f068b65cf5fdfb02018bb8f929..1c55ff12728a21a7c7e482606202e8904fdd0057 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc @@ -66,7 +66,7 @@ FlightModesComponentController::~FlightModesComponentController() void FlightModesComponentController::_init(void) { // FIXME: What about VTOL? That confuses the whole Flight Mode naming scheme - _fixedWing = _uas->getSystemType() == MAV_TYPE_FIXED_WING; + _fixedWing = _vehicle->vehicleType() == MAV_TYPE_FIXED_WING; // We need to know min and max for channel in order to calculate percentage range for (int channel=0; channel<_chanMax; channel++) { diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index c4ef8a386441dc11229cafec589180ec55647b64..014350998f02902815211422ad7dce4898d0f1d5 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -94,32 +94,32 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) Q_ASSERT(_vehicle); if (parametersReady()) { - _airframeComponent = new AirframeComponent(_vehicle->uas(), this); + _airframeComponent = new AirframeComponent(_vehicle, this); Q_CHECK_PTR(_airframeComponent); _airframeComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); - _radioComponent = new RadioComponent(_vehicle->uas(), this); + _radioComponent = new RadioComponent(_vehicle, this); Q_CHECK_PTR(_radioComponent); _radioComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_radioComponent)); - _flightModesComponent = new FlightModesComponent(_vehicle->uas(), this); + _flightModesComponent = new FlightModesComponent(_vehicle, this); Q_CHECK_PTR(_flightModesComponent); _flightModesComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent)); - _sensorsComponent = new SensorsComponent(_vehicle->uas(), this); + _sensorsComponent = new SensorsComponent(_vehicle, this); Q_CHECK_PTR(_sensorsComponent); _sensorsComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent)); - _powerComponent = new PowerComponent(_vehicle->uas(), this); + _powerComponent = new PowerComponent(_vehicle, this); Q_CHECK_PTR(_powerComponent); _powerComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_powerComponent)); - _safetyComponent = new SafetyComponent(_vehicle->uas(), this); + _safetyComponent = new SafetyComponent(_vehicle, this); Q_CHECK_PTR(_safetyComponent); _safetyComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); diff --git a/src/AutoPilotPlugins/PX4/PX4Component.cc b/src/AutoPilotPlugins/PX4/PX4Component.cc index 85fd90983146fa8a01195163930ad4694539b254..567869bf975c740b499a7e40f4d1c1a2314a65a7 100644 --- a/src/AutoPilotPlugins/PX4/PX4Component.cc +++ b/src/AutoPilotPlugins/PX4/PX4Component.cc @@ -28,10 +28,10 @@ #include "Fact.h" #include "AutoPilotPlugin.h" -PX4Component::PX4Component(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - VehicleComponent(uas, autopilot, parent) +PX4Component::PX4Component(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + VehicleComponent(vehicle, autopilot, parent) { - Q_ASSERT(uas); + Q_ASSERT(vehicle); Q_ASSERT(autopilot); } diff --git a/src/AutoPilotPlugins/PX4/PX4Component.h b/src/AutoPilotPlugins/PX4/PX4Component.h index 74455ceda59946efb651c0b80d0fc01644abb4e7..0283506e8568555c08cf74bd440921d46db4a290 100644 --- a/src/AutoPilotPlugins/PX4/PX4Component.h +++ b/src/AutoPilotPlugins/PX4/PX4Component.h @@ -37,7 +37,7 @@ class PX4Component : public VehicleComponent Q_OBJECT public: - PX4Component(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + PX4Component(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); /// @brief Returns an list of parameter names for which a change should cause the setupCompleteChanged /// signal to be emitted. Last element is signalled by NULL. diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.cc b/src/AutoPilotPlugins/PX4/PowerComponent.cc index c0883eba8dc8500cc20568dab3fd82103eb6b4ba..16be86cbfc025f8c0ac823ac0653e948128465ac 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponent.cc @@ -28,8 +28,8 @@ #include "QGCQmlWidgetHolder.h" #include "PX4AutoPilotPlugin.h" -PowerComponent::PowerComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - PX4Component(uas, autopilot, parent), +PowerComponent::PowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + PX4Component(vehicle, autopilot, parent), _name(tr("Power")) { } diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.h b/src/AutoPilotPlugins/PX4/PowerComponent.h index ca0841c8d3ebc9fa53163f5bac60e1134b0d6439..7d21055243095488cb511a621bd96c2d51809ba5 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.h +++ b/src/AutoPilotPlugins/PX4/PowerComponent.h @@ -35,7 +35,7 @@ class PowerComponent : public PX4Component Q_OBJECT public: - PowerComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + PowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from PX4Component virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/PX4/RadioComponent.cc b/src/AutoPilotPlugins/PX4/RadioComponent.cc index 02e9f8320b63272b759a4ef1f2d42793f127e16d..0f95fb1a421179fb1692426fe317ca4199f3e072 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponent.cc +++ b/src/AutoPilotPlugins/PX4/RadioComponent.cc @@ -28,8 +28,8 @@ #include "QGCQmlWidgetHolder.h" #include "PX4AutoPilotPlugin.h" -RadioComponent::RadioComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - PX4Component(uas, autopilot, parent), +RadioComponent::RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + PX4Component(vehicle, autopilot, parent), _name(tr("Radio")) { } diff --git a/src/AutoPilotPlugins/PX4/RadioComponent.h b/src/AutoPilotPlugins/PX4/RadioComponent.h index 7e4bf57768ffe2eb90f49d77f8152a703a54dc1b..15f718140916e1f6e1e38963d43eef42af248ac6 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponent.h +++ b/src/AutoPilotPlugins/PX4/RadioComponent.h @@ -36,7 +36,7 @@ class RadioComponent : public PX4Component Q_OBJECT public: - RadioComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from PX4Component virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.cc b/src/AutoPilotPlugins/PX4/SafetyComponent.cc index e7b5da65ee7953eb07e3412fe4c6cb350c84be41..27dfb9fd8060f9436189c929e97d893836825906 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.cc +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.cc @@ -28,8 +28,8 @@ #include "QGCQmlWidgetHolder.h" #include "PX4AutoPilotPlugin.h" -SafetyComponent::SafetyComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - PX4Component(uas, autopilot, parent), +SafetyComponent::SafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + PX4Component(vehicle, autopilot, parent), _name(tr("Safety")) { } diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.h b/src/AutoPilotPlugins/PX4/SafetyComponent.h index cdcc68bfaacbd308db816effc0ac71e74b6b22bb..7b11f59b888432ecc546a65e224d997f9f6a6106 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.h +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.h @@ -36,7 +36,7 @@ class SafetyComponent : public PX4Component Q_OBJECT public: - SafetyComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + SafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from PX4Component virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.cc b/src/AutoPilotPlugins/PX4/SensorsComponent.cc index c6311fcf5061f723caecb78058fb5e91d3499115..5fb1d00de3449a3db5a1d013d3cd16262d193ba4 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.cc @@ -31,8 +31,8 @@ // These two list must be kept in sync -SensorsComponent::SensorsComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : - PX4Component(uas, autopilot, parent), +SensorsComponent::SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : + PX4Component(vehicle, autopilot, parent), _name(tr("Sensors")) { @@ -87,11 +87,15 @@ QStringList SensorsComponent::setupCompleteChangedTriggerList(void) const QStringList triggers; triggers << "CAL_MAG0_ID" << "CAL_GYRO0_ID" << "CAL_ACC0_ID"; - if (_uas->getSystemType() == MAV_TYPE_FIXED_WING || - _uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR || - _uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR || - _uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR) { - triggers << "SENS_DPRES_OFF"; + switch (_vehicle->vehicleType()) { + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_VTOL_DUOROTOR: + case MAV_TYPE_VTOL_QUADROTOR: + case MAV_TYPE_VTOL_TILTROTOR: + triggers << "SENS_DPRES_OFF"; + break; + default: + break; } return triggers; @@ -115,13 +119,16 @@ QUrl SensorsComponent::summaryQmlSource(void) const { QString summaryQml; - if (_uas->getSystemType() == MAV_TYPE_FIXED_WING || - _uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR || - _uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR || - _uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR) { - summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml"; - } else { - summaryQml = "qrc:/qml/SensorsComponentSummary.qml"; + switch (_vehicle->vehicleType()) { + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_VTOL_DUOROTOR: + case MAV_TYPE_VTOL_QUADROTOR: + case MAV_TYPE_VTOL_TILTROTOR: + summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml"; + break; + default: + summaryQml = "qrc:/qml/SensorsComponentSummary.qml"; + break; } return QUrl::fromUserInput(summaryQml); diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.h b/src/AutoPilotPlugins/PX4/SensorsComponent.h index 5ce0e00fcd9eeae9063b0a3dabb89692d5648f1f..aa79968d338871950a5eb1e57bf6ad62afd3cdd7 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.h +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.h @@ -35,7 +35,7 @@ class SensorsComponent : public PX4Component Q_OBJECT public: - SensorsComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); // Virtuals from PX4Component virtual QStringList setupCompleteChangedTriggerList(void) const; diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 583dc6963e88e19ec8a87af2259115ce33bdaf21..9988d989899f2a9cc66c56d567127283d667ee89 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -445,12 +445,15 @@ void SensorsComponentController::_refreshParams(void) bool SensorsComponentController::fixedWing(void) { - UASInterface* uas = _autopilot->vehicle()->uas(); - Q_ASSERT(uas); - return uas->getSystemType() == MAV_TYPE_FIXED_WING || - uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR || - uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR || - uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR; + switch (_vehicle->vehicleType()) { + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_VTOL_DUOROTOR: + case MAV_TYPE_VTOL_QUADROTOR: + case MAV_TYPE_VTOL_TILTROTOR: + return true; + default: + return false; + } } void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 81b07f758f8a5e84482c6d4ba44287820baf50d6..57a80deff0938b6c2f328e53d6c5d4ad48421aee 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -708,9 +708,9 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream) return errors; } -void ParameterLoader::writeParametersToStream(QTextStream &stream, const QString& name) +void ParameterLoader::writeParametersToStream(QTextStream &stream) { - stream << "# Onboard parameters for system " << name << "\n"; + stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n"; stream << "#\n"; stream << "# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)\n"; diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 483111daace3b7df3c06971542be245281ce3e81..5a82e81fd7a782d67a1a4b1569887ac4f19a0feb 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -85,7 +85,7 @@ public: /// Returns error messages from loading QString readParametersFromStream(QTextStream& stream); - void writeParametersToStream(QTextStream &stream, const QString& name); + void writeParametersToStream(QTextStream &stream); signals: /// Signalled when the full set of facts are ready diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 1b929d739bda7a96ccf134ff48485ffb71f4b709..2ab725937a32a467e74f34dedd4cce0d47af0312 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -97,6 +97,8 @@ void APMParameterMetaData::_loadParameterFactMetaData(void) /// Override from FactLoad which connects the meta data to the fact void APMParameterMetaData::addMetaDataToFact(Fact* fact) { + _loadParameterFactMetaData(); + // FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data FactMetaData* metaData = new FactMetaData(fact->type(), fact); diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 1cb1cdc77d1484307483bdf334e578eea3b13b19..d57d0a00c35f6ae6a14f488bc89cbc7d353463bb 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -27,9 +27,8 @@ #include "ArduCopterFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h" -IMPLEMENT_QGC_SINGLETON(ArduCopterFirmwarePlugin, ArduCopterFirmwarePlugin) - -APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : APMCustomMode(mode, settable) +APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : + APMCustomMode(mode, settable) { QMap enumToString; enumToString.insert(STABILIZE, "Stabilize"); diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 62a70c54247b68dcb948de0a29fd079a1ae1c1fe..4f8cfa1b40305f398fd6ff4a05987d8be85e8b6e 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -61,16 +61,9 @@ public: class ArduCopterFirmwarePlugin : public APMFirmwarePlugin { Q_OBJECT - - DECLARE_QGC_SINGLETON(ArduCopterFirmwarePlugin, ArduCopterFirmwarePlugin) public: - -protected: - /// All access to singleton is through instance() ArduCopterFirmwarePlugin(void); - -private: }; #endif diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc index ea6eaed674222aef9438fe6f514c3e8d72a896a4..34032628872d1b9f9ce7a22cd80289eee1da3bc0 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc @@ -27,9 +27,8 @@ #include "ArduPlaneFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h" -IMPLEMENT_QGC_SINGLETON(ArduPlaneFirmwarePlugin, ArduPlaneFirmwarePlugin) - -APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable) : APMCustomMode(mode, settable) +APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable) + : APMCustomMode(mode, settable) { QMap enumToString; enumToString.insert(MANUAL, "Manual"); diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h index 84913452e38b1eae1909e62ff5b2fca61b3e0ec1..ace48a0f9764fde7fe0cb84284a9bc3bed236775 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h @@ -59,16 +59,9 @@ public: class ArduPlaneFirmwarePlugin : public APMFirmwarePlugin { Q_OBJECT - - DECLARE_QGC_SINGLETON(ArduPlaneFirmwarePlugin, ArduPlaneFirmwarePlugin) public: - -protected: - /// All access to singleton is through instance() ArduPlaneFirmwarePlugin(void); - -private: }; #endif diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index d620714d75acd969a9c3bdfc75453a36ef01ada2..7fcd85946873e6c3dedaa1f0805c5b139a54ca72 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -27,9 +27,8 @@ #include "ArduRoverFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h" -IMPLEMENT_QGC_SINGLETON(ArduRoverFirmwarePlugin, ArduRoverFirmwarePlugin) - -APMRoverMode::APMRoverMode(uint32_t mode, bool settable) : APMCustomMode(mode, settable) +APMRoverMode::APMRoverMode(uint32_t mode, bool settable) + : APMCustomMode(mode, settable) { QMap enumToString; enumToString.insert(MANUAL, "Manual"); diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index b50971cb8d0fa2803812128be44345ead8ae273e..58a1a288ca90f2074a46d7fe7b512229f9682e3d 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -59,16 +59,9 @@ public: class ArduRoverFirmwarePlugin : public APMFirmwarePlugin { Q_OBJECT - - DECLARE_QGC_SINGLETON(ArduRoverFirmwarePlugin, ArduRoverFirmwarePlugin) public: - -protected: - /// All access to singleton is through instance() ArduRoverFirmwarePlugin(void); - -private: }; #endif diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index df226d9f431fb7bd22e0c8b7deec14aa25bb5b02..d1d27199fbb197818688a7e2954fa2769eb11443 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -27,7 +27,6 @@ #ifndef FirmwarePlugin_H #define FirmwarePlugin_H -#include "QGCSingleton.h" #include "QGCMAVLink.h" #include "VehicleComponent.h" #include "AutoPilotPlugin.h" @@ -46,7 +45,7 @@ class Vehicle; /// in the base class supports mavlink generic firmware. Override the base clase virtuals /// to create you firmware specific plugin. -class FirmwarePlugin : public QGCSingleton +class FirmwarePlugin : public QObject { Q_OBJECT @@ -110,9 +109,6 @@ public: /// Adds the parameter meta data to the Fact virtual void addMetaDataToFact(Fact* fact) = 0; - -protected: - FirmwarePlugin(void) { }; }; #endif diff --git a/src/FirmwarePlugin/FirmwarePluginManager.cc b/src/FirmwarePlugin/FirmwarePluginManager.cc index aec991eaa3792d5f59cd769c12e87c9bff25b725..3cd337323da9dd6fe912058041c7c956bb280b50 100644 --- a/src/FirmwarePlugin/FirmwarePluginManager.cc +++ b/src/FirmwarePlugin/FirmwarePluginManager.cc @@ -1,5 +1,5 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station (c) 2009 - 2014 QGROUNDCONTROL PROJECT @@ -31,51 +31,67 @@ #include "APM/ArduRoverFirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h" +FirmwarePluginManager::FirmwarePluginManager(QGCApplication* app) + : QGCTool(app) + , _arduCopterFirmwarePlugin(NULL) + , _arduPlaneFirmwarePlugin(NULL) + , _arduRoverFirmwarePlugin(NULL) + , _genericFirmwarePlugin(NULL) + , _px4FirmwarePlugin(NULL) +{ + +} + +FirmwarePluginManager::~FirmwarePluginManager() +{ + delete _arduCopterFirmwarePlugin; + delete _arduPlaneFirmwarePlugin; + delete _arduRoverFirmwarePlugin; + delete _genericFirmwarePlugin; + delete _px4FirmwarePlugin; +} + FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) { switch (autopilotType) { - case MAV_AUTOPILOT_ARDUPILOTMEGA: - switch (vehicleType) { - case MAV_TYPE_QUADROTOR: - case MAV_TYPE_HEXAROTOR: - case MAV_TYPE_OCTOROTOR: - case MAV_TYPE_TRICOPTER: - case MAV_TYPE_COAXIAL: - case MAV_TYPE_HELICOPTER: - return ArduCopterFirmwarePlugin::instance(); - break; - case MAV_TYPE_FIXED_WING: - return ArduPlaneFirmwarePlugin::instance(); - break; - case MAV_TYPE_GROUND_ROVER: - case MAV_TYPE_SURFACE_BOAT: - case MAV_TYPE_SUBMARINE: - return ArduRoverFirmwarePlugin::instance(); - break; - case MAV_TYPE_GENERIC: - case MAV_TYPE_ANTENNA_TRACKER: - case MAV_TYPE_GCS: - case MAV_TYPE_AIRSHIP: - case MAV_TYPE_FREE_BALLOON: - case MAV_TYPE_ROCKET: - case MAV_TYPE_FLAPPING_WING: - case MAV_TYPE_KITE: - case MAV_TYPE_ONBOARD_CONTROLLER: - case MAV_TYPE_VTOL_DUOROTOR: - case MAV_TYPE_VTOL_QUADROTOR: - case MAV_TYPE_VTOL_TILTROTOR: - case MAV_TYPE_VTOL_RESERVED2: - case MAV_TYPE_VTOL_RESERVED3: - case MAV_TYPE_VTOL_RESERVED4: - case MAV_TYPE_VTOL_RESERVED5: - case MAV_TYPE_GIMBAL: - default: - return GenericFirmwarePlugin::instance(); - break; + case MAV_AUTOPILOT_ARDUPILOTMEGA: + switch (vehicleType) { + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + if (!_arduCopterFirmwarePlugin) { + _arduCopterFirmwarePlugin = new ArduCopterFirmwarePlugin; + } + return _arduCopterFirmwarePlugin; + case MAV_TYPE_FIXED_WING: + if (!_arduPlaneFirmwarePlugin) { + _arduPlaneFirmwarePlugin = new ArduPlaneFirmwarePlugin; } - case MAV_AUTOPILOT_PX4: - return PX4FirmwarePlugin::instance(); + return _arduPlaneFirmwarePlugin; + case MAV_TYPE_GROUND_ROVER: + case MAV_TYPE_SURFACE_BOAT: + case MAV_TYPE_SUBMARINE: + if (!_arduRoverFirmwarePlugin) { + _arduRoverFirmwarePlugin = new ArduRoverFirmwarePlugin; + } + return _arduRoverFirmwarePlugin; default: - return GenericFirmwarePlugin::instance(); + break; + } + case MAV_AUTOPILOT_PX4: + if (!_px4FirmwarePlugin) { + _px4FirmwarePlugin = new PX4FirmwarePlugin; + } + return _px4FirmwarePlugin; + default: + break; + } + + if (!_genericFirmwarePlugin) { + _genericFirmwarePlugin = new GenericFirmwarePlugin; } + return _genericFirmwarePlugin; } diff --git a/src/FirmwarePlugin/FirmwarePluginManager.h b/src/FirmwarePlugin/FirmwarePluginManager.h index 84f32ca95c86bf22410e402cc80b32afa1c27568..6a6550177e689fb392d6b0248a624f272ec394ba 100644 --- a/src/FirmwarePlugin/FirmwarePluginManager.h +++ b/src/FirmwarePlugin/FirmwarePluginManager.h @@ -34,6 +34,11 @@ #include "QGCToolbox.h" class QGCApplication; +class ArduCopterFirmwarePlugin; +class ArduPlaneFirmwarePlugin; +class ArduRoverFirmwarePlugin; +class PX4FirmwarePlugin; +class GenericFirmwarePlugin; /// FirmwarePluginManager is a singleton which is used to return the correct FirmwarePlugin for a MAV_AUTOPILOT type. @@ -42,13 +47,21 @@ class FirmwarePluginManager : public QGCTool Q_OBJECT public: - FirmwarePluginManager(QGCApplication* app) : QGCTool(app) { } + FirmwarePluginManager(QGCApplication* app); + ~FirmwarePluginManager(); /// Returns appropriate plugin for autopilot type. /// @param autopilotType Type of autopilot to return plugin for. /// @param vehicleType Vehicle type of autopilot to return plugin for. /// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT. FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType); + +private: + ArduCopterFirmwarePlugin* _arduCopterFirmwarePlugin; + ArduPlaneFirmwarePlugin* _arduPlaneFirmwarePlugin; + ArduRoverFirmwarePlugin* _arduRoverFirmwarePlugin; + GenericFirmwarePlugin* _genericFirmwarePlugin; + PX4FirmwarePlugin* _px4FirmwarePlugin; }; #endif diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index a14c949c56a48d8d8364f24816c5171611bf467f..6e748b911c05deee6738e7cc6b6d1e59a0b82846 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -29,13 +29,6 @@ #include -IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin) - -GenericFirmwarePlugin::GenericFirmwarePlugin(void) -{ - -} - QList GenericFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) { Q_UNUSED(vehicle); diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index 6d6f210415d72a8567efcc248086f567618cb8ba..5eaa175c7b70f4d5e7850d3c06ad5f92eb931205 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -32,8 +32,6 @@ class GenericFirmwarePlugin : public FirmwarePlugin { Q_OBJECT - - DECLARE_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin) public: // Overrides from FirmwarePlugin @@ -49,9 +47,6 @@ public: virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact); virtual QString getDefaultComponentIdParam(void) const { return QString(); } - -private: - GenericFirmwarePlugin(void); }; #endif diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index fdc36ec0076315d7392fc715fd1f3a79208f9937..b45215bc98947a30d7c5859f19dcf732d13ed72f 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -29,8 +29,6 @@ #include -IMPLEMENT_QGC_SINGLETON(PX4FirmwarePlugin, FirmwarePlugin) - enum PX4_CUSTOM_MAIN_MODE { PX4_CUSTOM_MAIN_MODE_MANUAL = 1, PX4_CUSTOM_MAIN_MODE_ALTCTL, @@ -88,11 +86,6 @@ static const struct Modes2Name rgModes2Name[] = { }; -PX4FirmwarePlugin::PX4FirmwarePlugin(void) -{ - -} - QList PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) { Q_UNUSED(vehicle); diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 0c67ef4594f3138b8f9b4fa6803210eb4569bfb9..216d53657e5ca2e8252923964e6f188f9e8705d7 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -34,11 +34,8 @@ class PX4FirmwarePlugin : public FirmwarePlugin { Q_OBJECT - DECLARE_QGC_SINGLETON(PX4FirmwarePlugin, FirmwarePlugin) - public: // Overrides from FirmwarePlugin - virtual bool isCapable(FirmwareCapabilities capabilities); virtual QList componentsForVehicle(AutoPilotPlugin* vehicle); virtual QStringList flightModes(void); @@ -52,9 +49,6 @@ public: virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } private: - /// All access to singleton is through AutoPilotPluginManager::instance - PX4FirmwarePlugin(void); - PX4ParameterMetaData _parameterMetaData; }; diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index 9e370fc3891dcda3333e2c7b1f739f991fc3ce3e..ce4ddf090b2d11081d4f5e042f195856bf9bcfe8 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -347,6 +347,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) /// Override from FactLoad which connects the meta data to the fact void PX4ParameterMetaData::addMetaDataToFact(Fact* fact) { + _loadParameterFactMetaData(); if (_mapParameterName2FactMetaData.contains(fact->name())) { fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]); } else { diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index caca9f4a2ad59b74874c9607babf130e3fc1ebae..418794a2a43bab8d38cf463c0169b4483230c39d 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -85,11 +85,6 @@ Item { FlightDisplayViewController { id: _controller } - MissionController { - id: _missionController - Component.onCompleted: start(false /* editMode */) - } - function reloadContents() { if(_flightVideo) { _flightVideo.visible = false diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index a6473655caf9ec7bf3518a327ef98d2db62411d5..4133640a93c3586426dfba7577f478faea63ddc1 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -54,6 +54,11 @@ FlightMap { } } + MissionController { + id: _missionController + Component.onCompleted: start(false /* editMode */) + } + // Home position MissionItemIndicator { label: "H" diff --git a/src/HomePositionManager.cc b/src/HomePositionManager.cc index 14b06ba1b72d5006dc64174f37657c3a1d8cf079..01f39b4ddcb20ce7d5289d32de9b9f6634728d56 100644 --- a/src/HomePositionManager.cc +++ b/src/HomePositionManager.cc @@ -117,62 +117,7 @@ void HomePositionManager::_loadSettings(void) if (_homePositions.count() == 0) { _homePositions.append(new HomePosition("ETH Campus", QGeoCoordinate(47.3769, 8.549444, 470.0), this)); - } - - // Deprecated settings for old editor - - settings.beginGroup("QGC_UASMANAGER"); - bool changed = setHomePosition(settings.value("HOMELAT", homeLat).toDouble(), - settings.value("HOMELON", homeLon).toDouble(), - settings.value("HOMEALT", homeAlt).toDouble()); - - // Make sure to fire the change - this will - // make sure widgets get the signal once - if (!changed) - { - emit homePositionChanged(homeLat, homeLon, homeAlt); - } - - settings.endGroup(); -} - -bool HomePositionManager::setHomePosition(double lat, double lon, double alt) -{ - // Checking for NaN and infitiny - // and checking for borders - bool changed = false; - if (!isnan(lat) && !isnan(lon) && !isnan(alt) - && !isinf(lat) && !isinf(lon) && !isinf(alt) - && lat <= 90.0 && lat >= -90.0 && lon <= 180.0 && lon >= -180.0) - { - - if (fabs(homeLat - lat) > 1e-7) changed = true; - if (fabs(homeLon - lon) > 1e-7) changed = true; - if (fabs(homeAlt - alt) > 0.5f) changed = true; - - if (changed) - { - homeLat = lat; - homeLon = lon; - homeAlt = alt; - - emit homePositionChanged(homeLat, homeLon, homeAlt); - } - } - return changed; -} - -bool HomePositionManager::setHomePositionAndNotify(double lat, double lon, double alt) -{ - // Checking for NaN and infitiny - // and checking for borders - bool changed = setHomePosition(lat, lon, alt); - - if (changed) { - qgcApp()->toolbox()->multiVehicleManager()->setHomePositionForAllVehicles(homeLat, homeLon, homeAlt); - } - - return changed; + } } void HomePositionManager::updateHomePosition(const QString& name, const QGeoCoordinate& coordinate) diff --git a/src/HomePositionManager.h b/src/HomePositionManager.h index 0b3d2d5e42b1bf04aabafe4fe51b18ed5591d548..e9158178a99589393d37788a6c0fd33545182ffb 100644 --- a/src/HomePositionManager.h +++ b/src/HomePositionManager.h @@ -112,21 +112,6 @@ public: return homeAlt; } -public slots: - - // Deprecated methods - - /** @brief Set the current home position, but do not change it on the UAVs */ - bool setHomePosition(double lat, double lon, double alt); - - /** @brief Set the current home position on all UAVs*/ - bool setHomePositionAndNotify(double lat, double lon, double alt); - - -signals: - /** @brief Current home position changed */ - void homePositionChanged(double lat, double lon, double alt); - protected: double homeLat; double homeLon; diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index beca8faabde96f4dabcc04b6b471604374daac4f..899327f93cca337806fcd8087b9e55929822492c 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -49,7 +49,6 @@ #include "QGCMessageBox.h" #include "MainWindow.h" #include "UDPLink.h" -#include "QGCSingleton.h" #include "LinkManager.h" #include "HomePositionManager.h" #include "UASMessageHandler.h" @@ -322,7 +321,11 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) QGCApplication::~QGCApplication() { - _destroySingletons(); + MainWindow* mainWindow = MainWindow::instance(); + if (mainWindow) { + delete mainWindow; + } + shutdownVideoStreaming(); delete _toolbox; } @@ -433,8 +436,6 @@ bool QGCApplication::_initForNormalAppBoot(void) { QSettings settings; - _createSingletons(); - #ifdef __mobile__ _styleIsDark = false; #else @@ -573,37 +574,6 @@ QGCApplication* qgcApp(void) return QGCApplication::_app; } -/// @brief We create all the non-ui based singletons here instead of allowing them to be created randomly -/// by calls to instance. The reason being that depending on boot sequence the singleton may end -/// up being creating on something other than the main thread. -void QGCApplication::_createSingletons(void) -{ - // No dependencies - FirmwarePlugin* firmwarePlugin = GenericFirmwarePlugin::_createSingleton(); - Q_UNUSED(firmwarePlugin); - Q_ASSERT(firmwarePlugin); - - // No dependencies - firmwarePlugin = PX4FirmwarePlugin::_createSingleton(); - firmwarePlugin = ArduCopterFirmwarePlugin::_createSingleton(); - firmwarePlugin = ArduPlaneFirmwarePlugin::_createSingleton(); - firmwarePlugin = ArduRoverFirmwarePlugin::_createSingleton(); -} - -void QGCApplication::_destroySingletons(void) -{ - MainWindow* mainWindow = MainWindow::instance(); - if (mainWindow) { - delete mainWindow; - } - - GenericFirmwarePlugin::_deleteSingleton(); - PX4FirmwarePlugin::_deleteSingleton(); - ArduCopterFirmwarePlugin::_deleteSingleton(); - ArduPlaneFirmwarePlugin::_deleteSingleton(); - ArduRoverFirmwarePlugin::_deleteSingleton(); -} - void QGCApplication::informationMessageBoxOnMainThread(const QString& title, const QString& msg) { QGCMessageBox::information(title, msg); diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 08fb609cfadefa33c0a7fc6b6e5add5706dc7de2..084950bb9bf1aabe30f8fad05bee7d63cc6a3626 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -168,8 +168,6 @@ private slots: void _missingParamsDisplay(void); private: - void _createSingletons(void); - void _destroySingletons(void); void _loadCurrentStyle(void); static const char* _settingsVersionKey; ///< Settings key which hold settings version diff --git a/src/QGCSingleton.cc b/src/QGCSingleton.cc deleted file mode 100644 index 24da38cdfbf1da8ebb17d7b74d770af44f48c586..0000000000000000000000000000000000000000 --- a/src/QGCSingleton.cc +++ /dev/null @@ -1,31 +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 Base class for global singletons -/// -/// @author Don Gagne - -#include "QGCSingleton.h" -#include "QGCApplication.h" - diff --git a/src/QGCSingleton.h b/src/QGCSingleton.h deleted file mode 100644 index 2f4ea01ff5abc754cb051142c953a93fccfb78d4..0000000000000000000000000000000000000000 --- a/src/QGCSingleton.h +++ /dev/null @@ -1,152 +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 -/// @author Don Gagne - -#ifndef QGCSINGLETON_H -#define QGCSINGLETON_H - -#include -#include - -/// @def DECLARE_QGC_SINGLETON -/// Include this macro in your Derived Class definition -/// @param className Derived Class name -/// @param interfaceName If your class is accessed through an interface specify that, if not specify Derived class name. -#define DECLARE_QGC_SINGLETON(className, interfaceName) \ - public: \ - static interfaceName* instance(bool nullOk = false); \ - static void setMockInstance(interfaceName* mock); \ - static interfaceName* _createSingleton(void); \ - static void _deleteSingleton(void); \ - private: \ - static interfaceName* _instance; \ - static interfaceName* _mockInstance; \ - static interfaceName* _realInstance; \ - -/// @def IMPLEMENT_QGC_SINGLETON -/// Include this macro in your Derived Class implementation -/// @param className Derived Class name -/// @param interfaceName If your class is accessed through an interface specify that, if not specify Derived class name. -#define IMPLEMENT_QGC_SINGLETON(className, interfaceName) \ - interfaceName* className::_instance = NULL; \ - interfaceName* className::_mockInstance = NULL; \ - interfaceName* className::_realInstance = NULL; \ - \ - interfaceName* className::_createSingleton(void) \ - { \ - Q_ASSERT(_instance == NULL); \ - _instance = new className; \ - return _instance; \ - } \ - \ - void className::_deleteSingleton(void) \ - { \ - if (className::_instance) { \ - className* instance = qobject_cast(className::_instance); \ - Q_ASSERT_X(instance != NULL, "QGCSingleton", "If you hit this assert you may have forgotten to clear a Mock instance"); \ - className::_instance = NULL; \ - delete instance; \ - } \ - } \ - \ - interfaceName* className::instance(bool nullOk) \ - { \ - if (!nullOk) { \ - Q_ASSERT_X(_instance, "QGCSingleton", "Request for singleton that is NULL. If you hit this, then you have likely run into a startup or shutdown sequence bug (possibly intermittent)."); \ - } \ - return _instance; \ - } \ - \ - void className::setMockInstance(interfaceName* mock) \ - { \ - if (mock) { \ - Q_ASSERT(_instance); \ - Q_ASSERT(!_realInstance); \ - \ - _realInstance = _instance; \ - _instance = dynamic_cast(mock); \ - Q_ASSERT(_instance); \ - _mockInstance = mock; \ - } else { \ - Q_ASSERT(_instance); \ - Q_ASSERT(_realInstance); \ - \ - _instance = _realInstance; \ - _realInstance = NULL; \ - _mockInstance = NULL; \ - } \ - } - -class QGCApplication; -class UnitTest; - -/// This is the base class for all app global singletons -/// -/// All global singletons are created/destroyed at boot time by QGCApplication::_createSingletons and destroyed by QGC::Application::_destroySingletons. -/// This is done in order to make sure they are all created on the main thread. As such no other code other than Unit Test -/// code has access to the constructor/destructor. QGCSingleton supports replacing singletons with a mock implementation. -/// In this case your object must derive from an interface which in turn derives from QGCSingleton. Youu can then use -/// the setMock method to add and remove you mock implementation. See HomePositionManager example usage. In order to provide the -/// appropriate methods to make all this work you need to use the DECLARE_QGC_SINGLETON and IMPLEMENT_QGC_SINGLETON -/// macros as follows: -/// @code{.unparsed} -/// // Header file -/// -/// class MySingleton : public QGCSingleton { -/// Q_OBJECT -/// -/// DECLARE_QGC_SINGLETON(MySingleton, MySingleton) -/// -/// ... -/// -/// private: -/// // Constructor/Desctructor private since all access is through the singleton methods -/// MySingleton(QObject* parent == NULL); -/// ~MySingleton(); -/// -/// ... -/// } -/// -/// // Code file -/// -/// IMPLEMENT_QGC_SINGLETON(MySingleton, MySingleton) -/// -/// MySingleton::MySingleton(QObject* parent) : -/// QGCSigleton(parent) -/// { -/// } -/// -/// // Other class methods... -/// -/// @endcode -/// The example above does not use an inteface so the second parameter to the macro is the class name as well. - -class QGCSingleton : public QObject -{ - Q_OBJECT - -}; - -#endif diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index 026edc8247526c41c2eb97332697cbc595d0afb0..6ba5ac765c6e99955207cb901ca5c23d8a668f6c 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -30,6 +30,8 @@ #include "UAS.h" #include "QGCApplication.h" +QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog") + MultiVehicleManager::MultiVehicleManager(QGCApplication* app) : QGCTool(app) , _activeVehicleAvailable(false) @@ -97,6 +99,8 @@ bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId /// and all other right things happen when the Vehicle goes away. void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle) { + qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1"; + _vehicleBeingDeleted = vehicle; // Remove from map @@ -133,6 +137,8 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle) void MultiVehicleManager::_deleteVehiclePhase2 (void) { + qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2"; + /// Qml has been notified of vehicle about to go away and should be disconnected from it by now. /// This means we can now clear the active vehicle property and delete the Vehicle for real. @@ -157,6 +163,8 @@ void MultiVehicleManager::_deleteVehiclePhase2 (void) void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle) { + qCDebug(MultiVehicleManagerLog) << "setActiveVehicle" << vehicle; + if (vehicle != _activeVehicle) { if (_activeVehicle) { _activeVehicle->setActive(false); @@ -180,6 +188,8 @@ void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle) void MultiVehicleManager::_setActiveVehiclePhase2(void) { + qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2"; + // Now we signal the new active vehicle _activeVehicle = _vehicleBeingSetActive; emit activeVehicleChanged(_activeVehicle); @@ -212,13 +222,6 @@ void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady) } } -void MultiVehicleManager::setHomePositionForAllVehicles(double lat, double lon, double alt) -{ - for (int i=0; i< _vehicles.count(); i++) { - qobject_cast(_vehicles[i])->uas()->setHomePosition(lat, lon, alt); - } -} - void MultiVehicleManager::saveSetting(const QString &name, const QString& value) { QSettings settings; diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h index badc782ca9171e6c08c9a1872da06168e361cec9..b12c200248f1f312a258dcd91f37cadbee84e606 100644 --- a/src/Vehicle/MultiVehicleManager.h +++ b/src/Vehicle/MultiVehicleManager.h @@ -31,6 +31,7 @@ #include "QGCMAVLink.h" #include "QmlObjectListModel.h" #include "QGCToolbox.h" +#include "QGCLoggingCategory.h" class FirmwarePluginManager; class AutoPilotPluginManager; @@ -38,6 +39,8 @@ class JoystickManager; class QGCApplication; class MAVLinkProtocol; +Q_DECLARE_LOGGING_CATEGORY(MultiVehicleManagerLog) + class MultiVehicleManager : public QGCTool { Q_OBJECT @@ -65,8 +68,6 @@ public: Q_INVOKABLE Vehicle* getVehicleById(int vehicleId); - void setHomePositionForAllVehicles(double lat, double lon, double alt); - UAS* activeUas(void) { return _activeVehicle ? _activeVehicle->uas() : NULL; } QList vehicles(void); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f83189622c95101a5ac07091c44f2ab70de14911..b6820994850aa418ad969d6a342d9b7e0bbf677e 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -90,8 +90,6 @@ Vehicle::Vehicle(LinkInterface* link, , _batteryPercent(0.0) , _batteryConsumed(-1.0) , _currentHeartbeatTimeout(0) - , _waypointDistance(0.0) - , _currentWaypoint(0) , _satelliteCount(-1) , _satelliteLock(0) , _updateCount(0) @@ -154,15 +152,12 @@ Vehicle::Vehicle(LinkInterface* link, connect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout); connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining); connect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged); - connect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName); - connect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType); connect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc); UAS* pUas = dynamic_cast(_mav); if(pUas) { _setSatelliteCount(pUas->getSatelliteCount(), QString("")); connect(pUas, &UAS::satelliteCountChanged, this, &Vehicle::_setSatelliteCount); } - _setSystemType(_mav, _mav->getSystemType()); _loadSettings(); @@ -188,8 +183,6 @@ Vehicle::Vehicle(LinkInterface* link, Vehicle::~Vehicle() { - qDebug() << "~Vehicle"; - delete _missionManager; _missionManager = NULL; @@ -519,12 +512,6 @@ void Vehicle::_updateNavigationControllerData(UASInterface *uas, float, float, f * Internal */ -bool Vehicle::_isAirplane() { - if (_mav) - return _mav->isAirplane(); - return false; -} - void Vehicle::_addChange(int id) { if(!_changes.contains(id)) { @@ -639,86 +626,6 @@ void Vehicle::_updateState(UASInterface*, QString name, QString) } } -void Vehicle::_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 Vehicle::_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 Vehicle::_heartbeatTimeout(bool timeout, unsigned int ms) { unsigned int elapsed = ms; @@ -756,39 +663,6 @@ void Vehicle::_setSatLoc(UASInterface*, int fix) } } -void Vehicle::_updateWaypointDistance(double distance) -{ - if (_waypointDistance != distance) { - _waypointDistance = distance; - emit waypointDistanceChanged(); - } -} - -void Vehicle::_updateCurrentWaypoint(quint16 id) -{ - if (_currentWaypoint != id) { - _currentWaypoint = id; - emit currentWaypointChanged(); - } -} - -void Vehicle::_updateWaypointViewOnly(int, MissionItem* /*wp*/) -{ - /* - bool changed = false; - for(int i = 0; i < _waypoints.count(); i++) { - if(_waypoints[i].sequenceNumber() == wp->sequenceNumber()) { - _waypoints[i] = *wp; - changed = true; - break; - } - } - if(changed) { - emit waypointListChanged(); - } - */ -} - void Vehicle::_handleTextMessage(int newCount) { // Reset? @@ -939,16 +813,25 @@ bool Vehicle::joystickEnabled(void) void Vehicle::setJoystickEnabled(bool enabled) { + // The magic parameter will go away, + // until then don't mess with the logic here! Fact* fact = _autopilotPlugin->getParameterFact(FactSystem::defaultComponentId, "COM_RC_IN_MODE"); if (!fact) { qCWarning(JoystickLog) << "Missing COM_RC_IN_MODE parameter"; } - if (fact->value().toInt() != 2) { + // Any value greater than one + // indicates special handling on + // the autopilot side. Force the + // joystick to on. + if (fact->value().toInt() > 1) { + // Mandatory in this setting + _joystickEnabled = true; + } else { fact->setValue(enabled ? 1 : 0); + _joystickEnabled = enabled; } - _joystickEnabled = enabled; _startJoystick(_joystickEnabled); _saveSettings(); } @@ -1158,6 +1041,10 @@ void Vehicle::_parametersReady(bool parametersReady) _missionManagerInitialRequestComplete = true; _missionManager->requestMissionItems(); } + + if (parametersReady) { + setJoystickEnabled(_joystickEnabled); + } } void Vehicle::_communicationInactivityTimedOut(void) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 0a0e833064a549d3e8bf64e4308ae36747faca0c..34f0b4b84b78fdf66fd73bd01d1e5583dd9ddb0d 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -63,9 +63,8 @@ public: JoystickManager* joystickManager); ~Vehicle(); - Q_PROPERTY(int id READ id CONSTANT) - Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT) - + Q_PROPERTY(int id READ id CONSTANT) + Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT) Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged) Q_PROPERTY(bool coordinateValid READ coordinateValid NOTIFY coordinateValidChanged) Q_PROPERTY(MissionManager* missionManager MEMBER _missionManager CONSTANT) @@ -78,54 +77,51 @@ public: Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged) Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT) + 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 coordinateChanged) + Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged) + Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) + Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) + Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged) + Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged) + Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) + Q_PROPERTY(int satelliteLock READ satelliteLock NOTIFY satelliteLockChanged) + Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) + Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT) + Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged) + Q_PROPERTY(bool messageTypeNormal READ messageTypeNormal NOTIFY messageTypeChanged) + Q_PROPERTY(bool messageTypeWarning READ messageTypeWarning NOTIFY messageTypeChanged) + Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged) + Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged) + Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged) + Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged) + Q_PROPERTY(int joystickMode READ joystickMode WRITE setJoystickMode NOTIFY joystickModeChanged) + Q_PROPERTY(QStringList joystickModes READ joystickModes CONSTANT) + Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged) + Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged) + + /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink + /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. + /// The remainder can be assigned to Vehicle actions. + /// @return -1: reserver all buttons, >0 number of buttons to reserve + Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT) + + Q_INVOKABLE QString getMavIconColor(); // Property accessors QGeoCoordinate coordinate(void) { return _coordinate; } bool coordinateValid(void) { return _coordinateValid; } - - Q_INVOKABLE QString getMavIconColor(); - - //-- System Messages - Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged) - Q_PROPERTY(bool messageTypeNormal READ messageTypeNormal NOTIFY messageTypeChanged) - Q_PROPERTY(bool messageTypeWarning READ messageTypeWarning NOTIFY messageTypeChanged) - Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged) - Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged) - Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged) - Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged) - //-- UAV Stats - 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 coordinateChanged) - Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged) - Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) - Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) - Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged) - 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(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT) QmlObjectListModel* missionItemsModel(void); - /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink - /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. - /// The remainder can be assigned to Vehicle actions. - /// @return -1: reserver all buttons, >0 number of buttons to reserve - Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT) typedef enum { JoystickModeRC, ///< Joystick emulates an RC Transmitter @@ -136,22 +132,16 @@ public: JoystickModeMax } JoystickMode_t; - /// The joystick mode associated with this vehicle. Joystick modes are stored keyed by mavlink system id. - Q_PROPERTY(int joystickMode READ joystickMode WRITE setJoystickMode NOTIFY joystickModeChanged) int joystickMode(void); void setJoystickMode(int mode); /// List of joystick mode names - Q_PROPERTY(QStringList joystickModes READ joystickModes CONSTANT) QStringList joystickModes(void); - // Enable/Disable joystick for this vehicle - Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged) bool joystickEnabled(void); void setJoystickEnabled(bool enabled); // Is vehicle active with respect to current active vehicle in QGC - Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged) bool active(void); void setActive(bool active); @@ -227,7 +217,6 @@ public: // Called when the message drop-down is invoked to clear current count void resetMessages(); - bool messageTypeNone () { return _currentMessageType == MessageNone; } bool messageTypeNormal () { return _currentMessageType == MessageNormal; } bool messageTypeWarning () { return _currentMessageType == MessageWarning; } @@ -251,12 +240,8 @@ public: double batteryVoltage () { return _batteryVoltage; } double batteryPercent () { return _batteryPercent; } double batteryConsumed () { return _batteryConsumed; } - 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; } ParameterLoader* getParameterLoader(void); @@ -302,13 +287,9 @@ signals: void batteryConsumedChanged (); void heartbeatTimeoutChanged(); void currentConfigChanged (); - void systemPixmapChanged (); void satelliteCountChanged (); void currentStateChanged (); - void systemNameChanged (); void satelliteLockChanged (); - void waypointDistanceChanged(); - void currentWaypointChanged (); private slots: void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message); @@ -324,9 +305,7 @@ private slots: 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); @@ -334,14 +313,9 @@ private slots: void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); void _updateBatteryConsumedChanged (UASInterface*, double current_consumed); void _updateState (UASInterface* 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, MissionItem* wp); private: bool _containsLink(LinkInterface* link); @@ -355,7 +329,6 @@ private: void _mapTrajectoryStart(void); void _mapTrajectoryStop(void); - bool _isAirplane (); void _addChange (int id); float _oneDecimal (float value); @@ -412,11 +385,7 @@ private: double _batteryPercent; double _batteryConsumed; QString _currentState; - QString _systemName; - QString _systemPixmap; unsigned int _currentHeartbeatTimeout; - double _waypointDistance; - quint16 _currentWaypoint; int _satelliteCount; int _satelliteLock; int _updateCount; diff --git a/src/VehicleSetup/SetupViewTest.cc b/src/VehicleSetup/SetupViewTest.cc index 11d29ba9efd2e02205160063adcb47c960a88816..3ab4c6f654ef9af6f89a0435a11cfa5736cb6a1b 100644 --- a/src/VehicleSetup/SetupViewTest.cc +++ b/src/VehicleSetup/SetupViewTest.cc @@ -63,10 +63,6 @@ void SetupViewTest::_clickThrough_test(void) QTest::qWait(1000); } - // On MainWindow close we should get a message box telling the user to disconnect first. - - setExpectedMessageBox(QGCMessageBox::Yes); - + _disconnectMockLink(); _closeMainWindow(); - checkExpectedMessageBox(); } diff --git a/src/VehicleSetup/VehicleComponent.cc b/src/VehicleSetup/VehicleComponent.cc index d9cf5f0d205f1df730a0811d19a18886a996d906..16df91fe21b987c884efa82cfcab13867658db49 100644 --- a/src/VehicleSetup/VehicleComponent.cc +++ b/src/VehicleSetup/VehicleComponent.cc @@ -27,12 +27,12 @@ #include "VehicleComponent.h" #include "AutoPilotPlugin.h" -VehicleComponent::VehicleComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : +VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : QObject(parent), - _uas(uas), + _vehicle(vehicle), _autopilot(autopilot) { - Q_ASSERT(uas); + Q_ASSERT(vehicle); Q_ASSERT(autopilot); } diff --git a/src/VehicleSetup/VehicleComponent.h b/src/VehicleSetup/VehicleComponent.h index 37c520ff4657961bb2431e135041ea8c23c6d1ef..d777e7ae92ed88f4f8b86097fbfadf9d38e7613e 100644 --- a/src/VehicleSetup/VehicleComponent.h +++ b/src/VehicleSetup/VehicleComponent.h @@ -31,7 +31,7 @@ #include #include -#include "UASInterface.h" +#include "Vehicle.h" class AutoPilotPlugin; @@ -53,7 +53,7 @@ class VehicleComponent : public QObject Q_PROPERTY(QString prerequisiteSetup READ prerequisiteSetup) public: - VehicleComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL); + VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); ~VehicleComponent(); virtual QString name(void) const = 0; @@ -73,8 +73,8 @@ signals: void setupCompleteChanged(bool setupComplete); protected: - UASInterface* _uas; - AutoPilotPlugin* _autopilot; + Vehicle* _vehicle; + AutoPilotPlugin* _autopilot; }; #endif diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index a60d5538502cd82a399aadba095b7838a6b294b5..0cb2598c8f8a563c9375fe0439454ec1852e6ada 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -198,13 +198,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) // Use the same shared pointer as LinkManager _connectedLinks.append(_linkMgr->sharedPointerForLink(link)); -#ifndef __mobile__ - if (_connectedLinks.count() == 1) { - // This is the first link, we need to start logging - _startLogging(); - } -#endif - // Send command to start MAVLink // XXX hacky but safe // Start NSH @@ -364,6 +357,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) #endif if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { +#ifndef __mobile__ + // Start loggin on first heartbeat + _startLogging(); +#endif + // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed. mavlink_heartbeat_t heartbeat; mavlink_msg_heartbeat_decode(&message, &heartbeat); @@ -657,20 +655,20 @@ bool MAVLinkProtocol::_closeLogFile(void) void MAVLinkProtocol::_startLogging(void) { - Q_ASSERT(!_tempLogFile.isOpen()); + if (!_tempLogFile.isOpen()) { + if (!_logSuspendReplay) { + if (!_tempLogFile.open()) { + emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. " + "Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName())); + _closeLogFile(); + _logSuspendError = true; + return; + } + + qDebug() << "Temp log" << _tempLogFile.fileName(); - if (!_logSuspendReplay) { - if (!_tempLogFile.open()) { - emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. " - "Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName())); - _closeLogFile(); - _logSuspendError = true; - return; + _logSuspendError = false; } - - qDebug() << "Temp log" << _tempLogFile.fileName(); - - _logSuspendError = false; } } diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index cf70786c3094fe5d79e0824c6b07d25a3d5cb51f..3fb78aad7e08cd5604976f37875243bce7bd6879 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -47,28 +47,30 @@ This file is part of the QGROUNDCONTROL project #include "QGCMessageBox.h" #include "HomePositionManager.h" #include "QGCApplication.h" +#include "Vehicle.h" +#include "UAS.h" // FlightGear _fgProcess start and connection is quite fragile. Uncomment the define below to get higher level of debug output // for tracking down problems. //#define DEBUG_FLIGHTGEAR_CONNECT -QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) : - flightGearVersion(3), - startupArguments(startupArguments), - _sensorHilEnabled(true), - barometerOffsetkPa(0.0f), - _udpCommSocket(NULL), - _fgProcess(NULL) +QGCFlightGearLink::QGCFlightGearLink(Vehicle* vehicle, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) + : _vehicle(vehicle) + , _udpCommSocket(NULL) + , _fgProcess(NULL) + , flightGearVersion(3) + , startupArguments(startupArguments) + , _sensorHilEnabled(true) + , barometerOffsetkPa(0.0f) { // We're doing it wrong - because the Qt folks got the API wrong: // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/ moveToThread(this); this->host = host; - this->port = port+mav->getUASID(); + this->port = port + _vehicle->id(); this->connectState = false; - this->currentPort = 49000+mav->getUASID(); - this->mav = mav; + this->currentPort = 49000 + _vehicle->id(); this->name = tr("FlightGear 3.0+ Link (port:%1)").arg(port); setRemoteHost(remoteHost); @@ -88,7 +90,7 @@ QGCFlightGearLink::~QGCFlightGearLink() /// @brief Runs the simulation thread. We do setup work here which needs to happen in the seperate thread. void QGCFlightGearLink::run() { - Q_ASSERT(mav); + Q_ASSERT(_vehicle); Q_ASSERT(!_fgProcessName.isEmpty()); // We communicate with FlightGear over a UDP _udpCommSocket @@ -100,16 +102,16 @@ void QGCFlightGearLink::run() // Connect to the various HIL signals that we use to then send information across the UDP protocol to FlightGear. - connect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), + connect(_vehicle->uas(), SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); connect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), - mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); + _vehicle->uas(), SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); connect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), - mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); + _vehicle->uas(), SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), - mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); + _vehicle->uas(), SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); connect(this, SIGNAL(sensorHilOpticalFlowChanged(quint64, qint16, qint16, float,float, quint8, float)), - mav, SLOT(sendHilOpticalFlow(quint64, qint16, qint16, float, float, quint8, float))); + _vehicle->uas(), SLOT(sendHilOpticalFlow(quint64, qint16, qint16, float, float, quint8, float))); // Start a new QProcess to run FlightGear in _fgProcess = new QProcess(this); @@ -131,7 +133,7 @@ void QGCFlightGearLink::run() // On Windows we need to full qualify the location of the excecutable. The call to setWorkingDirectory only // sets the QProcess context, not the QProcess::start context. For some strange reason this is not the case on // OSX. - QDir fgProcessFullyQualified(_fgProcessWorkingDirPath); + QDir fgProcessFullyQualified(_fgProcessWorkingDirPath); _fgProcessName = fgProcessFullyQualified.absoluteFilePath(_fgProcessName); #endif @@ -430,7 +432,7 @@ void QGCFlightGearLink::readBytes() zmag_body = mag_body(2); emit sensorHilRawImuChanged(QGC::groundTimeUsecs(), xacc, yacc, zacc, rollspeed, pitchspeed, yawspeed, - xmag_body, ymag_body, zmag_body, abs_pressure*1e-2f, diff_pressure*1e-2f, pressure_alt, temperature, fields_changed); //Pressure in hPa for mavlink + xmag_body, ymag_body, zmag_body, abs_pressure*1e-2f, diff_pressure*1e-2f, pressure_alt, temperature, fields_changed); //Pressure in hPa for _vehicle->uas()link // qDebug() << "sensorHilRawImuChanged " << xacc << yacc << zacc << rollspeed << pitchspeed << yawspeed << xmag << ymag << zmag << abs_pressure << diff_pressure << pressure_alt << temperature; int gps_fix_type = 3; @@ -491,12 +493,12 @@ bool QGCFlightGearLink::disconnectSimulation() { disconnect(_fgProcess, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); - disconnect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); - disconnect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); - disconnect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); - disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); + disconnect(_vehicle->uas(), SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); + disconnect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), _vehicle->uas(), SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); + disconnect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), _vehicle->uas(), SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); + disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), _vehicle->uas(), SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); disconnect(this, SIGNAL(sensorHilOpticalFlowChanged(quint64, qint16, qint16, float,float, quint8, float)), - mav, SLOT(sendHilOpticalFlow(quint64, qint16, qint16, float, float, quint8, float))); + _vehicle->uas(), SLOT(sendHilOpticalFlow(quint64, qint16, qint16, float, float, quint8, float))); if (_fgProcess) { @@ -629,7 +631,7 @@ bool QGCFlightGearLink::connectSimulation() // have that information setup we start the thread which will call run, which will in turn // start the various FG processes on the seperate thread. - if (!mav) { + if (!_vehicle->uas()) { return false; } @@ -661,8 +663,14 @@ bool QGCFlightGearLink::connectSimulation() // that is pretty non-standard so we don't try to get fancy beyond hardcoding that path. fgAppDir.setPath("/Applications"); fgAppName = "FlightGear.app"; - _fgProcessName = "./fgfs.sh"; - _fgProcessWorkingDirPath = "/Applications/FlightGear.app/Contents/Resources/"; + // new path + _fgProcessName = "./fgfs"; + _fgProcessWorkingDirPath = "/Applications/FlightGear.app/Contents/MacOS/"; + if(!QFileInfo(_fgProcessWorkingDirPath + _fgProcessName).exists()){ + // old path + _fgProcessName = "./fgfs.sh"; + _fgProcessWorkingDirPath = "/Applications/FlightGear.app/Contents/Resources/"; + } fgRootPathProposedList += "/Applications/FlightGear.app/Contents/Resources/data/"; #elif defined Q_OS_WIN32 _fgProcessName = "fgfs.exe"; @@ -846,7 +854,7 @@ bool QGCFlightGearLink::connectSimulation() _fgArgList += "--fg-aircraft=" + qgcAircraftDir; // Setup protocol we will be using to communicate with FlightGear - QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); + QString fgProtocol(_vehicle->vehicleType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); QString fgProtocolArg("--generic=socket,%1,300,127.0.0.1,%2,udp,%3"); _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); @@ -947,7 +955,7 @@ bool QGCFlightGearLink::connectSimulation() } // Start the engines to save a startup step - if (mav->getSystemType() == MAV_TYPE_QUADROTOR) { + if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) { // Start all engines of the quad _fgArgList << "--prop:/engines/engine[0]/running=true"; _fgArgList << "--prop:/engines/engine[1]/running=true"; diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index 269f4ac1cab3038de562df1a5f9ef31efb0d6c9b..9a9fe5aa048805f234a7d309257f6548469be7bf 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -38,18 +38,20 @@ This file is part of the QGROUNDCONTROL project #include #include #include -#include + +#include "LinkInterface.h" #include "QGCConfig.h" #include "UASInterface.h" #include "QGCHilLink.h" -#include +#include "QGCHilFlightGearConfiguration.h" +#include "Vehicle.h" class QGCFlightGearLink : public QGCHilLink { Q_OBJECT public: - QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); + QGCFlightGearLink(Vehicle* vehicle, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); ~QGCFlightGearLink(); bool isConnected(); @@ -135,20 +137,6 @@ public slots: void processError(QProcess::ProcessError err); protected: - QString name; - QHostAddress host; - QHostAddress currentHost; - quint16 currentPort; - quint16 port; - int id; - bool connectState; - - UASInterface* mav; - unsigned int flightGearVersion; - QString startupArguments; - bool _sensorHilEnabled; - float barometerOffsetkPa; - void setName(QString name); private slots: @@ -158,6 +146,7 @@ private slots: private: static bool _findUIArgument(const QStringList& uiArgList, const QString& argLabel, QString& argValue); + Vehicle* _vehicle; QString _fgProcessName; ///< FlightGear process to start QString _fgProcessWorkingDirPath; ///< Working directory to start FG process in, empty for none QStringList _fgArgList; ///< Arguments passed to FlightGear process @@ -166,6 +155,19 @@ private: QProcess* _fgProcess; ///< FlightGear process QString _fgProtocolFileFullyQualified; ///< Fully qualified file name for protocol file + + QString name; + QHostAddress host; + QHostAddress currentHost; + quint16 currentPort; + quint16 port; + int id; + bool connectState; + + unsigned int flightGearVersion; + QString startupArguments; + bool _sensorHilEnabled; + float barometerOffsetkPa; }; #endif // QGCFLIGHTGEARLINK_H diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc index 0322b2295b622c998ae3e7fc519a722f536de69a..bf5c77f5d1c649c5d93afdfd47472bee0e0ad06b 100644 --- a/src/comm/QGCJSBSimLink.cc +++ b/src/comm/QGCJSBSimLink.cc @@ -41,20 +41,20 @@ This file is part of the QGROUNDCONTROL project #include "QGC.h" #include "QGCMessageBox.h" -QGCJSBSimLink::QGCJSBSimLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) : - socket(NULL), - process(NULL), - startupArguments(startupArguments) +QGCJSBSimLink::QGCJSBSimLink(Vehicle* vehicle, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) + : _vehicle(vehicle) + , socket(NULL) + , process(NULL) + , startupArguments(startupArguments) { // We're doing it wrong - because the Qt folks got the API wrong: // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/ moveToThread(this); this->host = host; - this->port = port+mav->getUASID(); + this->port = port + _vehicle->id(); this->connectState = false; - this->currentPort = 49000+mav->getUASID(); - this->mav = mav; + this->currentPort = 49000 + _vehicle->id(); this->name = tr("JSBSim Link (port:%1)").arg(port); setRemoteHost(remoteHost); } @@ -75,7 +75,7 @@ void QGCJSBSimLink::run() { qDebug() << "STARTING FLIGHTGEAR LINK"; - if (!mav) return; + if (!_vehicle) return; socket = new QUdpSocket(this); socket->moveToThread(this); connectState = socket->bind(host, port, QAbstractSocket::ReuseAddressHint); @@ -84,15 +84,11 @@ void QGCJSBSimLink::run() process = new QProcess(this); - connect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); - connect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + connect(_vehicle->uas(), SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); + connect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), _vehicle->uas(), SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); - UAS* uas = dynamic_cast(mav); - if (uas) - { - uas->startHil(); - } + _vehicle->uas()->startHil(); //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate())); // Catch process error @@ -139,7 +135,7 @@ void QGCJSBSimLink::run() /*Prepare JSBSim Arguments */ - if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) { arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); } @@ -364,8 +360,8 @@ bool QGCJSBSimLink::disconnectSimulation() { disconnect(process, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); - disconnect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); - disconnect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + disconnect(_vehicle->uas(), SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); + disconnect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), _vehicle->uas(), SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); if (process) { diff --git a/src/comm/QGCJSBSimLink.h b/src/comm/QGCJSBSimLink.h index bb293cd511fb444ae6b67a8d3eada46a85dc220a..409d78aa4678f36e3dd2269307adbaf3e98f3512 100644 --- a/src/comm/QGCJSBSimLink.h +++ b/src/comm/QGCJSBSimLink.h @@ -40,8 +40,8 @@ This file is part of the QGROUNDCONTROL project #include #include #include "QGCConfig.h" -#include "UASInterface.h" #include "QGCHilLink.h" +#include "Vehicle.h" class QGCJSBSimLink : public QGCHilLink { @@ -49,7 +49,7 @@ class QGCJSBSimLink : public QGCHilLink //Q_INTERFACES(QGCJSBSimLinkInterface:LinkInterface) public: - QGCJSBSimLink(UASInterface* mav, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); + QGCJSBSimLink(Vehicle* vehicle, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); ~QGCJSBSimLink(); bool isConnected(); @@ -127,7 +127,8 @@ public slots: void setStartupArguments(QString startupArguments); -protected: +private: + Vehicle* _vehicle; QString name; QHostAddress host; QHostAddress currentHost; @@ -147,7 +148,6 @@ protected: QMutex statisticsMutex; QMutex dataMutex; QTimer refreshTimer; - UASInterface* mav; QProcess* process; unsigned int flightGearVersion; QString startupArguments; @@ -155,10 +155,6 @@ protected: bool _sensorHilEnabled; void setName(QString name); - -signals: - - }; #endif // QGCJSBSimLink_H diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index ef85146bf49bca85b17acaa7c94042036eee3624..93eb6755fcb46c0dfcf246af6719e58589d81a29 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -45,8 +45,8 @@ This file is part of the QGROUNDCONTROL project #include "QGCMessageBox.h" #include "HomePositionManager.h" -QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress localHost, quint16 localPort) : - mav(mav), +QGCXPlaneLink::QGCXPlaneLink(Vehicle* vehicle, QString remoteHost, QHostAddress localHost, quint16 localPort) : + _vehicle(vehicle), remoteHost(QHostAddress("127.0.0.1")), remotePort(49000), socket(NULL), @@ -156,7 +156,7 @@ void QGCXPlaneLink::setVersion(unsigned int version) **/ void QGCXPlaneLink::run() { - if (!mav) { + if (!_vehicle) { emit statusMessage("No MAV present"); return; } @@ -182,22 +182,15 @@ void QGCXPlaneLink::run() QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); - UAS* uas = dynamic_cast(mav); - if (uas) - { - connect(uas, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8)), Qt::QueuedConnection); - connect(uas, SIGNAL(hilActuatorsChanged(quint64, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(quint64,float,float,float,float,float,float,float,float)), Qt::QueuedConnection); + connect(_vehicle->uas(), SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8)), Qt::QueuedConnection); + connect(_vehicle->uas(), SIGNAL(hilActuatorsChanged(quint64, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(quint64,float,float,float,float,float,float,float,float)), Qt::QueuedConnection); - connect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), uas, SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), Qt::QueuedConnection); - connect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), uas, SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), Qt::QueuedConnection); - connect(this, SIGNAL(sensorHilGpsChanged(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), uas, SLOT(sendHilGps(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), Qt::QueuedConnection); - connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), uas, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), Qt::QueuedConnection); + connect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), _vehicle->uas(), SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), Qt::QueuedConnection); + connect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), _vehicle->uas(), SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), Qt::QueuedConnection); + connect(this, SIGNAL(sensorHilGpsChanged(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), _vehicle->uas(), SLOT(sendHilGps(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), Qt::QueuedConnection); + connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), _vehicle->uas(), SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), Qt::QueuedConnection); - uas->startHil(); - } else { - emit statusMessage(tr("Failed to connect to drone instance")); - return; - } + _vehicle->uas()->startHil(); #pragma pack(push, 1) struct iset_struct @@ -246,20 +239,13 @@ void QGCXPlaneLink::run() QGC::SLEEP::msleep(5); } - uas = dynamic_cast(mav); - if (uas) - { - disconnect(uas, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); - disconnect(uas, SIGNAL(hilActuatorsChanged(quint64, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(quint64,float,float,float,float,float,float,float,float))); - - disconnect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), uas, SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); - disconnect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), uas, SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); - disconnect(this, SIGNAL(sensorHilGpsChanged(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), uas, SLOT(sendHilGps(quint64,double,double,double,int,float,float,float,float,float,float,float,int))); - disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), uas, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); + disconnect(_vehicle->uas(), SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); + disconnect(_vehicle->uas(), SIGNAL(hilActuatorsChanged(quint64, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(quint64,float,float,float,float,float,float,float,float))); - // Do not toggle HIL state on the UAS - this is not the job of this link, but of the - // UAS object - } + disconnect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), _vehicle->uas(), SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + disconnect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), _vehicle->uas(), SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + disconnect(this, SIGNAL(sensorHilGpsChanged(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), _vehicle->uas(), SLOT(sendHilGps(quint64,double,double,double,int,float,float,float,float,float,float,float,int))); + disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), _vehicle->uas(), SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); connectState = false; @@ -368,7 +354,7 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost) void QGCXPlaneLink::updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8) { - if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) // Only update this for multirotors { @@ -450,19 +436,7 @@ void QGCXPlaneLink::updateControls(quint64 time, float rollAilerons, float pitch bool isFixedWing = true; - if (mav->getAirframe() == UASInterface::QGC_AIRFRAME_X8 || - mav->getAirframe() == UASInterface::QGC_AIRFRAME_VIPER_2_0 || - mav->getAirframe() == UASInterface::QGC_AIRFRAME_CAMFLYER_Q) - { - // de-mix delta-mixed inputs - // pitch input - mixed roll and pitch channels - p.f[0] = 0.5f * (rollAilerons - pitchElevator); - // roll input - mixed roll and pitch channels - p.f[1] = 0.5f * (rollAilerons + pitchElevator); - // yaw - p.f[2] = 0.0f; - } - else if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) { qDebug() << "MAV_TYPE_QUADROTOR"; @@ -621,7 +595,7 @@ void QGCXPlaneLink::readBytes() if (fabsf(groundspeed)<0.1f && alt_agl<1.0) { // TODO: Add centrip. acceleration to the current static acceleration implementation. - Eigen::Vector3f g(0, 0, -9.81f); + Eigen::Vector3f g(0, 0, -9.80665f); Eigen::Matrix3f R = euler_to_wRo(yaw, pitch, roll); Eigen::Vector3f gr = R.transpose().eval() * g; @@ -643,6 +617,7 @@ void QGCXPlaneLink::readBytes() } fields_changed |= (1 << 0) | (1 << 1) | (1 << 2); + emitUpdate = true; } // atmospheric pressure aircraft for XPlane 9 and 10 else if (p.index == 6) @@ -670,6 +645,8 @@ void QGCXPlaneLink::readBytes() rollspeed = p.f[1]; yawspeed = p.f[2]; fields_changed |= (1 << 3) | (1 << 4) | (1 << 5); + + emitUpdate = true; } else if ((xPlaneVersion == 10 && p.index == 17) || (xPlaneVersion == 9 && p.index == 18)) { @@ -1021,17 +998,17 @@ void QGCXPlaneLink::setRandomPosition() double offLon = rand() / static_cast(RAND_MAX) / 500.0 + 1.0/500.0; double offAlt = rand() / static_cast(RAND_MAX) * 200.0 + 100.0; - if (mav->getAltitudeAMSL() + offAlt < 0) + if (_vehicle->altitudeAMSL() + offAlt < 0) { offAlt *= -1.0; } - setPositionAttitude(mav->getLatitude() + offLat, - mav->getLongitude() + offLon, - mav->getAltitudeAMSL() + offAlt, - mav->getRoll(), - mav->getPitch(), - mav->getYaw()); + setPositionAttitude(_vehicle->latitude() + offLat, + _vehicle->longitude() + offLon, + _vehicle->altitudeAMSL() + offAlt, + _vehicle->roll(), + _vehicle->pitch(), + _vehicle->uas()->getYaw()); } void QGCXPlaneLink::setRandomAttitude() @@ -1043,9 +1020,9 @@ void QGCXPlaneLink::setRandomAttitude() double pitch = rand() / static_cast(RAND_MAX) * 2.0 - 1.0; double yaw = rand() / static_cast(RAND_MAX) * 2.0 - 1.0; - setPositionAttitude(mav->getLatitude(), - mav->getLongitude(), - mav->getAltitudeAMSL(), + setPositionAttitude(_vehicle->latitude(), + _vehicle->longitude(), + _vehicle->altitudeAMSL(), roll, pitch, yaw); diff --git a/src/comm/QGCXPlaneLink.h b/src/comm/QGCXPlaneLink.h index af0fb750a539b5aa3c5406115a7d9c57f1385c9c..faee171029fea94111bcc6a04eb89857f8c4f9fd 100644 --- a/src/comm/QGCXPlaneLink.h +++ b/src/comm/QGCXPlaneLink.h @@ -40,8 +40,8 @@ This file is part of the QGROUNDCONTROL project #include #include #include "QGCConfig.h" -#include "UASInterface.h" #include "QGCHilLink.h" +#include "Vehicle.h" class QGCXPlaneLink : public QGCHilLink { @@ -49,7 +49,7 @@ class QGCXPlaneLink : public QGCHilLink //Q_INTERFACES(QGCXPlaneLinkInterface:LinkInterface) public: - QGCXPlaneLink(UASInterface* mav, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress localHost = QHostAddress::Any, quint16 localPort = 49005); + QGCXPlaneLink(Vehicle* vehicle, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress localHost = QHostAddress::Any, quint16 localPort = 49005); ~QGCXPlaneLink(); /** @@ -164,7 +164,7 @@ public slots: void setRandomAttitude(); protected: - UASInterface* mav; + Vehicle* _vehicle; QString name; QHostAddress localHost; quint16 localPort; diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 1dac19e774bbb0e166b0eba453ead8c8b61c1e9c..a393337e6e48843a0947e58390afa1b6d3ffdcfa 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include #include #include "UDPLink.h" @@ -461,8 +462,38 @@ void UDPConfiguration::addHost(const QString& host, int port) if(ipAdd.isEmpty()) { qWarning() << "UDP:" << "Could not resolve host:" << host << "port:" << port; } else { - _hosts[ipAdd] = port; - //qDebug() << "UDP:" << "Adding Host:" << ipAdd << ":" << port; + + // In simulation and testing setups the vehicle and the GCS can be + // running on the same host. This leads to packets arriving through + // the local network or the loopback adapter, which makes it look + // like the vehicle is connected through two different links, + // complicating routing. + // + // We detect this case and force all traffic to a simulated instance + // onto the local loopback interface. + + bool not_local = true; + + // Run through all IPv4 interfaces and check if their canonical + // IP address in string representation matches the source IP address + foreach (const QHostAddress &address, QNetworkInterface::allAddresses()) { + if (address.protocol() == QAbstractSocket::IPv4Protocol) { + + if (ipAdd.endsWith(address.toString())) { + // This is a local address of the same host + not_local = false; + } + } + } + + if (not_local) { + // This is a normal remote host, add it using its IPv4 address + _hosts[ipAdd] = port; + //qDebug() << "UDP:" << "Adding Host:" << ipAdd << ":" << port; + } else { + // It is localhost, so talk to it through the IPv4 loopback interface + _hosts["127.0.0.1"] = port; + } } } } diff --git a/src/qgcunittest/UnitTest.cc b/src/qgcunittest/UnitTest.cc index 8d749c5ca84697d0dedd11cd62b43121e503eac2..b3f5b404c4cd9846ae96212c8eee14a9f04afd60 100644 --- a/src/qgcunittest/UnitTest.cc +++ b/src/qgcunittest/UnitTest.cc @@ -124,10 +124,6 @@ void UnitTest::init(void) _expectMissedFileDialog = false; _expectMissedMessageBox = false; - // Each test gets a clean global state - qgcApp()->_destroySingletons(); - qgcApp()->_createSingletons(); - MAVLinkProtocol::deleteTempLogFiles(); } @@ -152,8 +148,6 @@ void UnitTest::cleanup(void) QEXPECT_FAIL("", "Expecting failure due internal testing", Continue); } QCOMPARE(_missedFileDialogCount, 0); - - qgcApp()->_destroySingletons(); } void UnitTest::setExpectedMessageBox(QMessageBox::StandardButton response) @@ -423,5 +417,9 @@ void UnitTest::_closeMainWindow(bool cancelExpected) mainWindowSpy.wait(2000); QCOMPARE(mainWindowSpy.count(), cancelExpected ? 0 : 1); + + // This leaves enough time for any dangling Qml components to get cleaned up. + // This prevents qWarning from bad references in Qml + QTest::qWait(1000); } } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index a2b560333c2fdec9850919bc22e282ae26eacb25..8d0ff0bd04fd2abd2cef69b84aa2c7f372fcea45 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -59,10 +59,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi receiveDropRate(0), sendDropRate(0), - name(""), - type(MAV_TYPE_GENERIC), - airframe(QGC_AIRFRAME_GENERIC), - autopilot(vehicle->firmwareType()), base_mode(0), custom_mode(0), status(-1), @@ -91,13 +87,8 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi manualThrust(0), positionLock(false), - isLocalPositionKnown(false), isGlobalPositionKnown(false), - localX(0.0), - localY(0.0), - localZ(0.0), - latitude(0.0), longitude(0.0), altitudeAMSL(0.0), @@ -191,9 +182,7 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi color = UASInterface::getNextColor(); connect(&statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); - connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings())); statusTimeout.start(500); - readSettings(); } /** @@ -211,33 +200,6 @@ UAS::~UAS() simulation->deleteLater(); } #endif - writeSettings(); -} - -/** -* Saves the settings of name, airframe, autopilot type and battery specifications -* for the next instantiation of UAS. -*/ -void UAS::writeSettings() -{ - QSettings settings; - settings.beginGroup(QString("MAV%1").arg(uasId)); - settings.setValue("NAME", this->name); - settings.setValue("AIRFRAME", this->airframe); - settings.endGroup(); -} - -/** -* Reads in the settings: name, airframe, autopilot type, and battery specifications -* for the new UAS. -*/ -void UAS::readSettings() -{ - QSettings settings; - settings.beginGroup(QString("MAV%1").arg(uasId)); - this->name = settings.value("NAME", this->name).toString(); - this->airframe = settings.value("AIRFRAME", this->airframe).toInt(); - settings.endGroup(); } /** @@ -385,13 +347,6 @@ void UAS::receiveMessage(mavlink_message_t message) emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time); emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time); - // Set new type if it has changed - if (this->type != state.type) - { - this->autopilot = state.autopilot; - setSystemType(state.type); - } - QString audiostring = QString("System %1").arg(uasId); QString stateAudio = ""; QString modeAudio = ""; @@ -683,25 +638,16 @@ void UAS::receiveMessage(mavlink_message_t message) mavlink_msg_local_position_ned_decode(&message, &pos); quint64 time = getUnixTime(pos.time_boot_ms); - // Emit position always with component ID - emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); - if (!wrongComponent) { - setLocalX(pos.x); - setLocalY(pos.y); - setLocalZ(pos.z); - speedX = pos.vx; speedY = pos.vy; speedZ = pos.vz; // Emit - emit localPositionChanged(this, localX, localY, localZ, time); emit velocityChanged_NED(this, speedX, speedY, speedZ, time); positionLock = true; - isLocalPositionKnown = true; } } break; @@ -710,7 +656,6 @@ void UAS::receiveMessage(mavlink_message_t message) mavlink_global_vision_position_estimate_t pos; mavlink_msg_global_vision_position_estimate_decode(&message, &pos); quint64 time = getUnixTime(pos.usec); - emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time); } break; @@ -1065,46 +1010,6 @@ void UAS::receiveMessage(mavlink_message_t message) } } -/** -* Set the home position of the UAS. -* @param lat The latitude fo the home position -* @param lon The longitude of the home position -* @param alt The altitude of the home position -*/ -void UAS::setHomePosition(double lat, double lon, double alt) -{ - if (!_vehicle || blockHomePositionChanges) - return; - - QString uasName = (getUASName() == "")? - tr("UAS") + QString::number(getUASID()) - : getUASName(); - - QMessageBox::StandardButton button = QGCMessageBox::question(tr("Set a new home position for vehicle %1").arg(uasName), - tr("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location"), - QMessageBox::Yes | QMessageBox::Cancel, - QMessageBox::Cancel); - if (button == QMessageBox::Yes) - { - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt); - // Send message twice to increase chance that it reaches its goal - _vehicle->sendMessage(msg); - - // Send new home position to UAS - mavlink_set_gps_global_origin_t home; - home.target_system = uasId; - home.latitude = lat*1E7; - home.longitude = lon*1E7; - home.altitude = alt*1000; - qDebug() << "lat:" << home.latitude << " lon:" << home.longitude; - mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home); - _vehicle->sendMessage(msg); - } else { - blockHomePositionChanges = true; - } -} - void UAS::startCalibration(UASInterface::StartCalibrationType calType) { if (!_vehicle) { @@ -1533,32 +1438,6 @@ quint64 UAS::getUptime() const } } -bool UAS::isRotaryWing() -{ - switch (type) { - case MAV_TYPE_QUADROTOR: - /* fallthrough */ - case MAV_TYPE_COAXIAL: - case MAV_TYPE_HELICOPTER: - case MAV_TYPE_HEXAROTOR: - case MAV_TYPE_OCTOROTOR: - case MAV_TYPE_TRICOPTER: - return true; - default: - return false; - } -} - -bool UAS::isFixedWing() -{ - switch (type) { - case MAV_TYPE_FIXED_WING: - return true; - default: - return false; - } -} - //TODO update this to use the parameter manager / param data model instead void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramUnion) { @@ -1602,40 +1481,6 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue); } -/** -* @param systemType Type of MAV. -*/ -void UAS::setSystemType(int systemType) -{ - if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END)) - { - type = systemType; - - // If the airframe is still generic, change it to a close default type - if (airframe == 0) - { - switch (type) - { - case MAV_TYPE_FIXED_WING: - setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR); - break; - case MAV_TYPE_QUADROTOR: - setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH); - break; - case MAV_TYPE_HEXAROTOR: - setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER); - break; - default: - // Do nothing - break; - } - } - emit systemSpecsChanged(uasId); - emit systemTypeSet(this, type); - qDebug() << "TYPE CHANGED TO:" << type; - } -} - void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) { if (!_vehicle) { @@ -1887,29 +1732,6 @@ void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll } #endif -/** -* @return the type of the system -*/ -int UAS::getSystemType() -{ - return this->type; -} - -/** @brief Is it an airplane (or like one)?,..)*/ -bool UAS::isAirplane() -{ - switch(this->type) { - case MAV_TYPE_GENERIC: - case MAV_TYPE_FIXED_WING: - case MAV_TYPE_AIRSHIP: - case MAV_TYPE_FLAPPING_WING: - return true; - default: - break; - } - return false; -} - /** * Order the robot to start receiver pairing */ @@ -1940,10 +1762,10 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj stopHil(); delete simulation; } - simulation = new QGCFlightGearLink(this, options); + simulation = new QGCFlightGearLink(_vehicle, options); } - float noise_scaler = 0.002f; + float noise_scaler = 0.0001f; xacc_var = noise_scaler * 0.2914f; yacc_var = noise_scaler * 0.2914f; zacc_var = noise_scaler * 0.9577f; @@ -1953,10 +1775,10 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj xmag_var = noise_scaler * 0.0786f; ymag_var = noise_scaler * 0.0566f; zmag_var = noise_scaler * 0.0333f; - abs_pressure_var = noise_scaler * 1.1604f; - diff_pressure_var = noise_scaler * 0.3604f; - pressure_alt_var = noise_scaler * 1.1604f; - temperature_var = noise_scaler * 2.4290f; + abs_pressure_var = noise_scaler * 0.5604f; + diff_pressure_var = noise_scaler * 0.2604f; + pressure_alt_var = noise_scaler * 0.5604f; + temperature_var = noise_scaler * 0.7290f; // Connect Flight Gear Link link = dynamic_cast(simulation); @@ -1988,7 +1810,7 @@ void UAS::enableHilJSBSim(bool enable, QString options) stopHil(); delete simulation; } - simulation = new QGCJSBSimLink(this, options); + simulation = new QGCJSBSimLink(_vehicle, options); } // Connect Flight Gear Link link = dynamic_cast(simulation); @@ -2016,9 +1838,9 @@ void UAS::enableHilXPlane(bool enable) stopHil(); delete simulation; } - simulation = new QGCXPlaneLink(this); + simulation = new QGCXPlaneLink(_vehicle); - float noise_scaler = 0.0002f; + float noise_scaler = 0.0001f; xacc_var = noise_scaler * 0.2914f; yacc_var = noise_scaler * 0.2914f; zacc_var = noise_scaler * 0.9577f; @@ -2028,10 +1850,10 @@ void UAS::enableHilXPlane(bool enable) xmag_var = noise_scaler * 0.0786f; ymag_var = noise_scaler * 0.0566f; zmag_var = noise_scaler * 0.0333f; - abs_pressure_var = noise_scaler * 1.1604f; - diff_pressure_var = noise_scaler * 0.3604f; - pressure_alt_var = noise_scaler * 1.1604f; - temperature_var = noise_scaler * 2.4290f; + abs_pressure_var = noise_scaler * 0.5604f; + diff_pressure_var = noise_scaler * 0.2604f; + pressure_alt_var = noise_scaler * 0.5604f; + temperature_var = noise_scaler * 0.7290f; } // Connect X-Plane Link if (enable) @@ -2341,23 +2163,6 @@ void UAS::stopHil() } #endif -/** - * @return The name of this system as string in human-readable form - */ -QString UAS::getUASName(void) const -{ - QString result; - if (name == "") - { - result = tr("MAV ") + result.sprintf("%03d", getUASID()); - } - else - { - result = name; - } - return result; -} - /** * @rerturn the map of the components */ diff --git a/src/uas/UAS.h b/src/uas/UAS.h index cd52382c475d4ecdc89c794c27ba3ac7a8c0f946..45ab119d7f9e5597fd97819156bf42e3b2470ed4 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -71,15 +71,8 @@ public: /* MANAGEMENT */ - /** @brief The name of the robot */ - QString getUASName(void) const; /** @brief Get the unique system id */ int getUASID() const; - /** @brief Get the airframe */ - int getAirframe() const - { - return airframe; - } /** @brief Get the components */ QMap getComponents(); @@ -88,13 +81,9 @@ public: /** @brief Add one measurement and get low-passed voltage */ float filterVoltage(float value); - 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 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) @@ -248,11 +237,6 @@ public: return satelliteCount; } - virtual bool localPositionKnown() const - { - return isLocalPositionKnown; - } - virtual bool globalPositionKnown() const { return isGlobalPositionKnown; @@ -369,9 +353,6 @@ public: temperature_var = var; } - bool isRotaryWing(); - bool isFixedWing(); - friend class FileManager; protected: //COMMENTS FOR TEST UNIT @@ -387,10 +368,6 @@ protected: //COMMENTS FOR TEST UNIT QTimer statusTimeout; ///< Timer for various status timeouts /// BASIC UAS TYPE, NAME AND STATE - QString name; ///< Human-friendly name of the vehicle, e.g. bravo - unsigned char type; ///< UAS type (from type enum) - int airframe; ///< The airframe type - int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM uint8_t base_mode; ///< The current mode of the MAV uint32_t custom_mode; ///< The current mode of the MAV int status; ///< The current status of the MAV @@ -427,7 +404,6 @@ protected: //COMMENTS FOR TEST UNIT /// POSITION bool positionLock; ///< Status if position information is available or not - bool isLocalPositionKnown; ///< If the local position has been received for this MAV bool isGlobalPositionKnown; ///< If the global position has been received for this MAV double localX; @@ -502,8 +478,6 @@ protected: //COMMENTS FOR TEST UNIT #endif public: - /** @brief Set the current battery type */ - void setBattery(BatteryType type, int cells); /** @brief Get the current charge level */ float getChargeLevel(); /** @brief Get the human-readable status message for this code */ @@ -520,34 +494,10 @@ public: } #endif - int getSystemType(); - bool isAirplane(); - QImage getImage(); void requestImage(); - int getAutopilotType(){ - return autopilot; - } public slots: - /** @brief Set the autopilot type */ - void setAutopilotType(int apType) - { - autopilot = apType; - emit systemSpecsChanged(uasId); - } - /** @brief Set the type of airframe */ - void setSystemType(int systemType); - /** @brief Set the specific airframe type */ - void setAirframe(int airframe) - { - if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM)) - { - this->airframe = airframe; - emit systemSpecsChanged(uasId); - } - - } /** @brief Executes a command with 7 params */ void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component); @@ -620,9 +570,6 @@ public slots: /** @brief Update the system state */ void updateState(); - /** @brief Set world frame origin / home position at this GPS position */ - void setHomePosition(double lat, double lon, double alt); - void startCalibration(StartCalibrationType calType); void stopCalibration(void); @@ -686,12 +633,6 @@ protected: quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent -protected slots: - /** @brief Write settings to disk */ - void writeSettings(); - /** @brief Read settings from disk */ - void readSettings(); - private: void _say(const QString& text, int severity = 6); diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 8121e819bac0bf18cb49ec72bf1455347f91ddf2..24f5b8148c792b56e540e20626539cb828ec1da2 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -43,16 +43,6 @@ This file is part of the QGROUNDCONTROL project class FileManager; -enum BatteryType -{ - NICD = 0, - NIMH = 1, - LIION = 2, - LIPOLY = 3, - LIFE = 4, - AGZN = 5 -}; ///< The type of battery used - /** * @brief Interface for all robots. * @@ -67,17 +57,10 @@ public: /* MANAGEMENT */ - /** @brief The name of the robot **/ - virtual QString getUASName() const = 0; virtual int getUASID() const = 0; ///< Get the ID of the connected UAS /** @brief The time interval the robot is switched on **/ virtual quint64 getUptime() const = 0; - virtual double getLocalX() const = 0; - virtual double getLocalY() const = 0; - virtual double getLocalZ() const = 0; - virtual bool localPositionKnown() const = 0; - virtual double getLatitude() const = 0; virtual double getLongitude() const = 0; virtual double getAltitudeAMSL() const = 0; @@ -88,30 +71,8 @@ public: virtual double getPitch() const = 0; virtual double getYaw() const = 0; - /** @brief Set the airframe of this MAV */ - virtual int getAirframe() const = 0; - virtual FileManager* getFileManager() = 0; - enum Airframe { - QGC_AIRFRAME_GENERIC = 0, - QGC_AIRFRAME_EASYSTAR, - QGC_AIRFRAME_TWINSTAR, - QGC_AIRFRAME_MERLIN, - QGC_AIRFRAME_CHEETAH, - QGC_AIRFRAME_MIKROKOPTER, - QGC_AIRFRAME_REAPER, - QGC_AIRFRAME_PREDATOR, - QGC_AIRFRAME_COAXIAL, - QGC_AIRFRAME_PTERYX, - QGC_AIRFRAME_TRICOPTER, - QGC_AIRFRAME_HEXCOPTER, - QGC_AIRFRAME_X8, - QGC_AIRFRAME_VIPER_2_0, - QGC_AIRFRAME_CAMFLYER_Q, - QGC_AIRFRAME_END_OF_ENUM - }; - /** * @brief Get the color for this UAS * @@ -151,15 +112,6 @@ public: return colors[nextColor];//return the next color } - /** @brief Get the type of the system (airplane, quadrotor, helicopter,..)*/ - virtual int getSystemType() = 0; - /** @brief Is it an airplane (or like one)?,..)*/ - virtual bool isAirplane() = 0; - - /** @brief Get the type of the autopilot (PIXHAWK, APM, UDB, PPZ,..) */ - virtual int getAutopilotType() = 0; - virtual void setAutopilotType(int apType) = 0; - virtual QMap getComponents() = 0; QColor getColor() @@ -167,9 +119,6 @@ public: return color; } - static const unsigned int WAYPOINT_RADIUS_DEFAULT_FIXED_WING = 25; - static const unsigned int WAYPOINT_RADIUS_DEFAULT_ROTARY_WING = 5; - enum StartCalibrationType { StartCalibrationRadio, StartCalibrationGyro, @@ -204,18 +153,8 @@ public slots: /** @brief Executes a command **/ virtual void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) = 0; - /** @brief Selects the airframe */ - virtual void setAirframe(int airframe) = 0; - /** @brief Order the robot to pair its receiver **/ virtual void pairRX(int rxType, int rxSubType) = 0; - - virtual void setHomePosition(double lat, double lon, double alt) = 0; - - /** @brief Return if this a rotary wing */ - virtual bool isRotaryWing() = 0; - /** @brief Return if this is a fixed wing */ - virtual bool isFixedWing() = 0; /** @brief Send the full HIL state to the MAV */ #ifndef __mobile__ @@ -322,8 +261,6 @@ signals: void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec); /** @brief A user (or an autonomous mission or obstacle avoidance planner) requested to set a new setpoint */ void userPositionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired); - void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec); - void localPositionChanged(UASInterface*, int component, double x, double y, double z, quint64 usec); void globalPositionChanged(UASInterface*, double lat, double lon, double altAMSL, double altWGS84, quint64 usec); void altitudeChanged(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64 usec); /** @brief Update the status of one satellite used for localization */ @@ -339,8 +276,6 @@ signals: void imageStarted(int imgid, int width, int height, int depth, int channels); void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex); - /** @brief Emit the new system type */ - void systemTypeSet(UASInterface* uas, unsigned int type); /** @brief Attitude control enabled/disabled */ void attitudeControlEnabled(bool enabled); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index a9dac5061558f1bdb43d7a7dc47412ea0daa2b28..1f0a154fb4b8892cb4a68d5c5b63ae37b9e56877 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -60,7 +60,6 @@ This file is part of the QGROUNDCONTROL project #include "QGCUASFileViewMulti.h" #include "UASQuickView.h" #include "QGCTabbedInfoView.h" -#include "UASRawStatusView.h" #include "CustomCommandWidget.h" #include "QGCDockWidget.h" #include "UASInfoWidget.h" diff --git a/src/ui/QGCHilConfiguration.cc b/src/ui/QGCHilConfiguration.cc index 85a30b162cdb0aa95961424c558d21985c131230..ced0d796303386ecf09b17857e914632b5e8247d 100644 --- a/src/ui/QGCHilConfiguration.cc +++ b/src/ui/QGCHilConfiguration.cc @@ -29,6 +29,7 @@ #include "QGCHilFlightGearConfiguration.h" #include "QGCHilJSBSimConfiguration.h" #include "QGCHilXPlaneConfiguration.h" +#include "UAS.h" QGCHilConfiguration::QGCHilConfiguration(Vehicle* vehicle, QWidget *parent) : QWidget(parent) @@ -87,7 +88,7 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index) { // Ensure the sim exists and is disabled _vehicle->uas()->enableHilFlightGear(false, "", true, this); - QGCHilFlightGearConfiguration* hfgconf = new QGCHilFlightGearConfiguration(_vehicle->uas(), this); + QGCHilFlightGearConfiguration* hfgconf = new QGCHilFlightGearConfiguration(_vehicle, this); hfgconf->show(); ui->simulatorConfigurationLayout->addWidget(hfgconf); QGCFlightGearLink* fg = dynamic_cast(_vehicle->uas()->getHILSimulation()); @@ -113,17 +114,19 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index) connect(xplane, SIGNAL(statusMessage(QString)), ui->statusLabel, SLOT(setText(QString))); } } - else if (4) - { - // Ensure the sim exists and is disabled - _vehicle->uas()->enableHilJSBSim(false, ""); - QGCHilJSBSimConfiguration* hfgconf = new QGCHilJSBSimConfiguration(_vehicle->uas(), this); - hfgconf->show(); - ui->simulatorConfigurationLayout->addWidget(hfgconf); - QGCJSBSimLink* jsb = dynamic_cast(_vehicle->uas()->getHILSimulation()); - if (jsb) - { - connect(jsb, SIGNAL(statusMessage(QString)), ui->statusLabel, SLOT(setText(QString))); - } - } +// Disabling JSB Sim since its not well maintained, +// but as refactoring is pending we're not ditching the code yet +// else if (4) +// { +// // Ensure the sim exists and is disabled +// _vehicle->uas()->enableHilJSBSim(false, ""); +// QGCHilJSBSimConfiguration* hfgconf = new QGCHilJSBSimConfiguration(_vehicle, this); +// hfgconf->show(); +// ui->simulatorConfigurationLayout->addWidget(hfgconf); +// QGCJSBSimLink* jsb = dynamic_cast(_vehicle->uas()->getHILSimulation()); +// if (jsb) +// { +// connect(jsb, SIGNAL(statusMessage(QString)), ui->statusLabel, SLOT(setText(QString))); +// } +// } } diff --git a/src/ui/QGCHilConfiguration.ui b/src/ui/QGCHilConfiguration.ui index f80a307e3bae1cab6d28f8a7c93eb9b0998e7b9f..82e9cc10f947856056ae5f5bf8673f5b5fe0b416 100644 --- a/src/ui/QGCHilConfiguration.ui +++ b/src/ui/QGCHilConfiguration.ui @@ -52,11 +52,6 @@ X-Plane 9 - - - JSBSim - - @@ -69,7 +64,7 @@ - + diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index 33004797d43ffce54a2a2756b860de985bd1f919..e7e3c24697ca1b95a1e29f615c1839600c7fcab3 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -1,5 +1,6 @@ #include "QGCHilFlightGearConfiguration.h" #include "MainWindow.h" +#include "UAS.h" #include @@ -16,32 +17,30 @@ const char* QGCHilFlightGearConfiguration::_sensorHilKey = "SEN // the QGCFlightGearLink code instead. const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; -QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent) : - QWidget(parent), - _mav(mav), - _mavSettingsSubGroup(NULL), - _resetOptionsAction(tr("Reset to default options"), this) +QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(Vehicle* vehicle, QWidget *parent) + : QWidget(parent) + , _vehicle(vehicle) + , _mavSettingsSubGroup(NULL) + , _resetOptionsAction(tr("Reset to default options"), this) { - Q_ASSERT(_mav); - _ui.setupUi(this); QStringList items; - if (_mav->getSystemType() == MAV_TYPE_FIXED_WING) + if (_vehicle->vehicleType() == MAV_TYPE_FIXED_WING) { - items << "EasyStar"; + /*items << "EasyStar";*/ items << "Rascal110-JSBSim"; - items << "c172p"; + /*items << "c172p"; items << "YardStik"; - items << "Malolo1"; + items << "Malolo1";*/ _mavSettingsSubGroup = _mavSettingsSubGroupFixedWing; } - else if (_mav->getSystemType() == MAV_TYPE_QUADROTOR) + /*else if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) { items << "arducopter"; _mavSettingsSubGroup = _mavSettingsSubGroupQuadRotor; - } + }*/ else { // FIXME: Should disable all input, won't work. Show error message in the status label thing. @@ -118,12 +117,12 @@ void QGCHilFlightGearConfiguration::on_startButton_clicked() //XXX check validity of inputs QString options = _ui.optionsPlainTextEdit->toPlainText(); options.append(" --aircraft=" + _ui.aircraftComboBox->currentText()); - _mav->enableHilFlightGear(true, options, _ui.sensorHilCheckBox->isChecked(), this); + _vehicle->uas()->enableHilFlightGear(true, options, _ui.sensorHilCheckBox->isChecked(), this); } void QGCHilFlightGearConfiguration::on_stopButton_clicked() { - _mav->stopHil(); + _vehicle->uas()->stopHil(); } void QGCHilFlightGearConfiguration::on_barometerOffsetLineEdit_textChanged(const QString& baroOffset) diff --git a/src/ui/QGCHilFlightGearConfiguration.h b/src/ui/QGCHilFlightGearConfiguration.h index 0b72996c6b3282c21e42e1316271829eddc0636a..6ebd999b6f3383c8ee8c817865dd490536d4906e 100644 --- a/src/ui/QGCHilFlightGearConfiguration.h +++ b/src/ui/QGCHilFlightGearConfiguration.h @@ -5,7 +5,7 @@ #include "QGCHilLink.h" #include "QGCFlightGearLink.h" -#include "UAS.h" +#include "Vehicle.h" #include "ui_QGCHilFlightGearConfiguration.h" @@ -18,7 +18,7 @@ class QGCHilFlightGearConfiguration : public QWidget Q_OBJECT public: - explicit QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent = 0); + explicit QGCHilFlightGearConfiguration(Vehicle* vehicle, QWidget *parent = 0); ~QGCHilFlightGearConfiguration(); protected: @@ -31,8 +31,8 @@ private slots: void _showContextMenu(const QPoint& pt); private: + Vehicle* _vehicle; Ui::QGCHilFlightGearConfiguration _ui; - UAS* _mav; /// mav associated with this ui static const char* _settingsGroup; /// Top level settings group const char* _mavSettingsSubGroup; /// We maintain a settings sub group per mav type diff --git a/src/ui/QGCHilJSBSimConfiguration.cc b/src/ui/QGCHilJSBSimConfiguration.cc index d37602731b2526e40c8fab028170cc1a6e91feaf..4e958ae0bf3d4606a056237a9affe6bc1c0ca48f 100644 --- a/src/ui/QGCHilJSBSimConfiguration.cc +++ b/src/ui/QGCHilJSBSimConfiguration.cc @@ -2,16 +2,17 @@ #include "ui_QGCHilJSBSimConfiguration.h" #include "MainWindow.h" +#include "UAS.h" -QGCHilJSBSimConfiguration::QGCHilJSBSimConfiguration(UAS* mav,QWidget *parent) : - QWidget(parent), - mav(mav), - ui(new Ui::QGCHilJSBSimConfiguration) +QGCHilJSBSimConfiguration::QGCHilJSBSimConfiguration(Vehicle* vehicle, QWidget *parent) + : QWidget(parent) + , _vehicle(vehicle) + , ui(new Ui::QGCHilJSBSimConfiguration) { ui->setupUi(this); QStringList items = QStringList(); - if (mav->getSystemType() == MAV_TYPE_FIXED_WING) + if (_vehicle->vehicleType() == MAV_TYPE_FIXED_WING) { items << "EasyStar"; items << "Rascal110-JSBSim"; @@ -19,7 +20,7 @@ QGCHilJSBSimConfiguration::QGCHilJSBSimConfiguration(UAS* mav,QWidget *parent) : items << "YardStik"; items << "Malolo1"; } - else if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + else if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) { items << "arducopter"; } @@ -40,10 +41,10 @@ void QGCHilJSBSimConfiguration::on_startButton_clicked() //XXX check validity of inputs QString options = ui->optionsPlainTextEdit->toPlainText(); options.append(" --script=" + ui->aircraftComboBox->currentText()); - mav->enableHilJSBSim(true, options); + _vehicle->uas()->enableHilJSBSim(true, options); } void QGCHilJSBSimConfiguration::on_stopButton_clicked() { - mav->stopHil(); + _vehicle->uas()->stopHil(); } diff --git a/src/ui/QGCHilJSBSimConfiguration.h b/src/ui/QGCHilJSBSimConfiguration.h index d3156000663df081fee5957e06ab71349215197e..b03bdf4a0f16fa0251f058c8499918292a42edcb 100644 --- a/src/ui/QGCHilJSBSimConfiguration.h +++ b/src/ui/QGCHilJSBSimConfiguration.h @@ -5,7 +5,7 @@ #include "QGCHilLink.h" #include "QGCFlightGearLink.h" -#include "UAS.h" +#include "Vehicle.h" namespace Ui { class QGCHilJSBSimConfiguration; @@ -16,17 +16,16 @@ class QGCHilJSBSimConfiguration : public QWidget Q_OBJECT public: - explicit QGCHilJSBSimConfiguration(UAS* mav, QWidget *parent = 0); + explicit QGCHilJSBSimConfiguration(Vehicle* vehicle, QWidget *parent = 0); ~QGCHilJSBSimConfiguration(); -protected: - UAS* mav; - private slots: void on_startButton_clicked(); void on_stopButton_clicked(); private: + Vehicle* _vehicle; + Ui::QGCHilJSBSimConfiguration *ui; }; diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index 41a665d46d38e15eb8464dbada8fefc1401a88f3..0ab169cd36aa50d8b86f1142098ee69a6f62f70b 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -65,7 +65,7 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action, void QGCMAVLinkInspector::_vehicleAdded(Vehicle* vehicle) { - ui->systemComboBox->addItem(vehicle->uas()->getUASName(), vehicle->id()); + ui->systemComboBox->addItem(QString("Vehicle %1").arg(vehicle->id()), vehicle->id()); // Add a tree for a new UAS addUAStoTree(vehicle->id()); @@ -340,14 +340,7 @@ void QGCMAVLinkInspector::addUAStoTree(int sysId) { UASInterface* uas = vehicle->uas(); QStringList idstring; - if (uas->getUASName() == "") - { - idstring << tr("UAS ") + QString::number(uas->getUASID()); - } - else - { - idstring << uas->getUASName(); - } + idstring << QString("Vehicle %1").arg(uas->getUASID()); QTreeWidgetItem* uasWidget = new QTreeWidgetItem(idstring); uasWidget->setFirstColumnSpanned(true); uasTreeWidgetItems.insert(sysId,uasWidget); diff --git a/src/ui/QGCTabbedInfoView.cpp b/src/ui/QGCTabbedInfoView.cpp index 21b652c3cac26bfee6bdb26e340cf9e2c0aa8de5..e051c6d0011119da532699e1a1b94e67d398d37d 100644 --- a/src/ui/QGCTabbedInfoView.cpp +++ b/src/ui/QGCTabbedInfoView.cpp @@ -6,12 +6,8 @@ QGCTabbedInfoView::QGCTabbedInfoView(const QString& title, QAction* action, QWid { ui.setupUi(this); messageView = new UASMessageViewWidget(qgcApp()->toolbox()->uasMessageHandler(), this); - //actionsWidget = new UASActionsWidget(this); quickView = new UASQuickView(this); - //rawView = new UASRawStatusView(this); ui.tabWidget->addTab(quickView,"Quick"); - //ui.tabWidget->addTab(actionsWidget,"Actions"); - //ui.tabWidget->addTab(rawView,"Status"); ui.tabWidget->addTab(messageView,"Messages"); loadSettings(); @@ -19,7 +15,6 @@ QGCTabbedInfoView::QGCTabbedInfoView(const QString& title, QAction* action, QWid void QGCTabbedInfoView::addSource(MAVLinkDecoder *decoder) { m_decoder = decoder; - //rawView->addSource(decoder); quickView->addSource(decoder); } diff --git a/src/ui/QGCTabbedInfoView.h b/src/ui/QGCTabbedInfoView.h index f14c5ed5fa7c52e96337ab3838d5cdcf4c914761..7f90f7899c0fca7980b146ec856460377231ead7 100644 --- a/src/ui/QGCTabbedInfoView.h +++ b/src/ui/QGCTabbedInfoView.h @@ -5,7 +5,6 @@ #include "MAVLinkDecoder.h" #include "UASMessageView.h" #include "UASQuickView.h" -#include "UASRawStatusView.h" #include "ui_QGCTabbedInfoView.h" @@ -22,7 +21,6 @@ private: Ui::QGCTabbedInfoView ui; UASMessageViewWidget *messageView; UASQuickView *quickView; - UASRawStatusView *rawView; }; #endif // QGCTABBEDINFOVIEW_H diff --git a/src/ui/UASRawStatusView.cpp b/src/ui/UASRawStatusView.cpp deleted file mode 100644 index 1862ea7a3f34955b59a90edef6078407d85fb177..0000000000000000000000000000000000000000 --- a/src/ui/UASRawStatusView.cpp +++ /dev/null @@ -1,112 +0,0 @@ -#include "UASRawStatusView.h" -#include "MAVLinkDecoder.h" -#include "UASInterface.h" -#include "UAS.h" -#include -#include -UASRawStatusView::UASRawStatusView(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); - ui.tableWidget->setColumnCount(2); - ui.tableWidget->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOn); - ui.tableWidget->setShowGrid(false); - ui.tableWidget->setEditTriggers(QAbstractItemView::NoEditTriggers); - QTimer *timer = new QTimer(this); - connect(timer,SIGNAL(timeout()),this,SLOT(updateTableTimerTick())); - - // FIXME reinstate once fixed. - - //timer->start(2000); -} -void UASRawStatusView::addSource(MAVLinkDecoder *decoder) -{ - connect(decoder,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64))); -} -void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant &variant, const quint64 msec) -{ - Q_UNUSED(uasId); - Q_UNUSED(unit); - Q_UNUSED(msec); - - bool ok; - double value = variant.toDouble(&ok); - QMetaType::Type type = static_cast(variant.type()); - if(!ok || type == QMetaType::QString || type == QMetaType::QByteArray) - return; - - valueMap[name] = value; - if (nameToUpdateWidgetMap.contains(name)) - { - nameToUpdateWidgetMap[name]->setText(QString::number(value)); - } - else - { - m_tableDirty = true; - } - return; -} -void UASRawStatusView::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - m_tableDirty = true; -} - -void UASRawStatusView::updateTableTimerTick() -{ - if (m_tableDirty) - { - m_tableDirty = false; - int columncount = 2; - bool good = false; - while (!good) - { - ui.tableWidget->clear(); - ui.tableWidget->setRowCount(0); - ui.tableWidget->setColumnCount(columncount); - ui.tableWidget->horizontalHeader()->hide(); - ui.tableWidget->verticalHeader()->hide(); - int currcolumn = 0; - int currrow = 0; - int totalheight = 2 + ui.tableWidget->horizontalScrollBar()->height(); - bool broke = false; - for (QMap::const_iterator i=valueMap.constBegin();i!=valueMap.constEnd();i++) - { - if (ui.tableWidget->rowCount() < currrow+1) - { - ui.tableWidget->setRowCount(currrow+1); - } - ui.tableWidget->setItem(currrow,currcolumn,new QTableWidgetItem(i.key().split(".")[1])); - QTableWidgetItem *item = new QTableWidgetItem(QString::number(i.value())); - nameToUpdateWidgetMap[i.key()] = item; - ui.tableWidget->setItem(currrow,currcolumn+1,item); - ui.tableWidget->resizeRowToContents(currrow); - totalheight += ui.tableWidget->rowHeight(currrow); - currrow++; - if ((totalheight + ui.tableWidget->rowHeight(currrow-1)) > ui.tableWidget->height()) - { - currcolumn+=2; - totalheight = 2 + ui.tableWidget->horizontalScrollBar()->height(); - currrow = 0; - if (currcolumn >= columncount) - { - //We're over what we can do. Add a column and continue. - columncount+=2; - broke = true; - i = valueMap.constEnd(); // Ensure loop breakout. - break; - } - } - } - if (!broke) - { - good = true; - } - } - ui.tableWidget->resizeColumnsToContents(); - //ui.tableWidget->columnCount()-2 - } -} - -UASRawStatusView::~UASRawStatusView() -{ -} diff --git a/src/ui/UASRawStatusView.h b/src/ui/UASRawStatusView.h deleted file mode 100644 index 2da632c33a50ec28ed2019fcab8c71399e62f209..0000000000000000000000000000000000000000 --- a/src/ui/UASRawStatusView.h +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef UASRAWSTATUSVIEW_H -#define UASRAWSTATUSVIEW_H - -#include -#include "MAVLinkDecoder.h" -#include "ui_UASRawStatusView.h" - -class UASRawStatusView : public QWidget -{ - Q_OBJECT - -public: - explicit UASRawStatusView(QWidget *parent = 0); - ~UASRawStatusView(); - void addSource(MAVLinkDecoder *decoder); -private slots: - void updateTableTimerTick(); - void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant& value, const quint64 msec); -protected: - void resizeEvent(QResizeEvent *event); -private: - QMap valueMap; - QMap nameToUpdateWidgetMap; - Ui::UASRawStatusView ui; - bool m_tableDirty; -}; - -#endif // UASRAWSTATUSVIEW_H diff --git a/src/ui/UASRawStatusView.ui b/src/ui/UASRawStatusView.ui deleted file mode 100644 index d63c41dc8571c3e08d94a83a757cb45a456b40a5..0000000000000000000000000000000000000000 --- a/src/ui/UASRawStatusView.ui +++ /dev/null @@ -1,24 +0,0 @@ - - - UASRawStatusView - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - - - - - - diff --git a/tools/google_play_upload.py b/tools/google_play_upload.py new file mode 100755 index 0000000000000000000000000000000000000000..9d0ce41569ab37959eda7cd6a1eceeece9746c46 --- /dev/null +++ b/tools/google_play_upload.py @@ -0,0 +1,96 @@ +#!/usr/bin/python +# +# Copyright 2014 Marta Rodriguez. +# +# Licensed under the Apache License, Version 2.0 (the 'License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Uploads an apk to the beta track.""" + +import argparse + +from apiclient.discovery import build +import httplib2 +from oauth2client import client + +TRACK = 'beta' # Can be 'alpha', beta', 'production' or 'rollout' +SERVICE_ACCOUNT_EMAIL = ( + '868554619222-u4gvu4asjemc8n22o595j0fr2dg4012j@developer.gserviceaccount.com') + +# Declare command-line flags. +argparser = argparse.ArgumentParser(add_help=False) +argparser.add_argument('package_name', + help='The package name. Example: com.android.sample') +argparser.add_argument('apk_file', + nargs='?', + default='qgroundcontrol.apk', + help='The path to the APK file to upload.') + + +def main(): + # Load the key in PKCS 12 format that you downloaded from the Google APIs + # Console when you created your Service account. + f = file('android/Google_Play_Android_Developer-bb93ae7d61ca.p12', 'rb') + key = f.read() + f.close() + + # Create an httplib2.Http object to handle our HTTP requests and authorize it + # with the Credentials. Note that the first parameter, service_account_name, + # is the Email address created for the Service account. It must be the email + # address associated with the key that was created. + credentials = client.SignedJwtAssertionCredentials( + SERVICE_ACCOUNT_EMAIL, + key, + scope='https://www.googleapis.com/auth/androidpublisher') + http = httplib2.Http() + http = credentials.authorize(http) + + service = build('androidpublisher', 'v2', http=http) + + # Process flags and read their values. + flags = argparser.parse_args() + + package_name = flags.package_name + apk_file = flags.apk_file + + try: + edit_request = service.edits().insert(body={}, packageName=package_name) + result = edit_request.execute() + edit_id = result['id'] + + apk_response = service.edits().apks().upload( + editId=edit_id, + packageName=package_name, + media_body=apk_file).execute() + + print 'Version code %d has been uploaded' % apk_response['versionCode'] + + track_response = service.edits().tracks().update( + editId=edit_id, + track=TRACK, + packageName=package_name, + body={u'versionCodes': [apk_response['versionCode']]}).execute() + + print 'Track %s is set for version code(s) %s' % ( + track_response['track'], str(track_response['versionCodes'])) + + commit_request = service.edits().commit( + editId=edit_id, packageName=package_name).execute() + + print 'Edit "%s" has been committed' % (commit_request['id']) + + except client.AccessTokenRefreshError: + print ('The credentials have been revoked or expired, please re-run the ' + 'application to re-authorize') + +if __name__ == '__main__': + main() diff --git a/tools/update_android_version.sh b/tools/update_android_version.sh new file mode 100755 index 0000000000000000000000000000000000000000..cb81634fa50e60b662f1f7517997bc7eb64bbb92 --- /dev/null +++ b/tools/update_android_version.sh @@ -0,0 +1,12 @@ +#! /bin/bash + +MANIFEST_FILE=android/AndroidManifest.xml + +VERSIONCODE=`git rev-list master --first-parent --count` +VERSIONNAME=`git describe --always --tags | sed -e 's/^v//'` + +echo "VersionCode: ${VERSIONCODE}" +echo "VersionName: ${VERSIONNAME}" + +sed -i -e "s/android:versionCode=\"[0-9][0-9]*\"/android:versionCode=\"${VERSIONCODE}\"/" $MANIFEST_FILE +sed -i -e 's/versionName *= *"[^"]*"/versionName="'$VERSIONNAME'"/' $MANIFEST_FILE