diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 22a7361858e9cd259ddd1821160be0e16257c585..a1017cde7705a8159d03ca9407fb40a22fc47d4d 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -29,10 +29,12 @@ #include -#ifdef Q_OS_MAC - #include -#else - #include +#ifndef __mobile__ + #ifdef Q_OS_MAC + #include + #else + #include + #endif #endif QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog") @@ -51,6 +53,7 @@ const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { }; Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex) +#ifndef __mobile__ : _sdlIndex(sdlIndex) , _exitThread(false) , _name(name) @@ -61,7 +64,14 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI , _buttonCount(buttonCount) , _lastButtonBits(0) , _throttleMode(ThrottleModeCenterZero) +#endif // __mobile__ { +#ifdef __mobile__ + Q_UNUSED(name) + Q_UNUSED(axisCount) + Q_UNUSED(buttonCount) + Q_UNUSED(sdlIndex) +#else for (int i=0; i<_cAxes; i++) { _rgAxisValues[i] = 0; } @@ -71,6 +81,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI } _loadSettings(); +#endif // __mobile __ } Joystick::~Joystick() @@ -78,6 +89,8 @@ Joystick::~Joystick() } +#ifndef __mobile__ + void Joystick::_loadSettings(void) { QSettings settings; @@ -504,3 +517,5 @@ void Joystick::setEnabled(bool enabled) stopPolling(); } } + +#endif // __mobile__ diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 81f4a6862b485954da3de806d4f5a3bb4303c6d7..317768cd27ae699de38b97b512d3522fe774aaaa 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -61,9 +61,9 @@ public: ThrottleModeMax } ThrottleMode_t; +#ifndef __mobile__ Q_PROPERTY(QString name READ name CONSTANT) - Q_PROPERTY(bool calibrated MEMBER _calibrated NOTIFY calibratedChanged) Q_PROPERTY(bool enabled READ enabled WRITE setEnabled NOTIFY enabledChanged) Q_PROPERTY(int buttonCount MEMBER _buttonCount CONSTANT) @@ -148,7 +148,6 @@ private: int _rgAxisValues[_cAxes]; Calibration_t _rgCalibration[_cAxes]; int _rgFunctionAxis[maxFunction]; - static const char* _rgFunctionSettingsKey[maxFunction]; static const int _cButtons = 12; bool _rgButtonValues[_cButtons]; @@ -156,7 +155,11 @@ private: quint16 _lastButtonBits; ThrottleMode_t _throttleMode; +#endif // __mobile__ +private: + static const char* _rgFunctionSettingsKey[maxFunction]; + static const char* _settingsGroup; static const char* _calibratedSettingsKey; static const char* _buttonActionSettingsKey; diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index e8c28570f45b7f5d9b936004917b5edfc9241b9f..d45bec4814034a03a0b72653c3259244591887dc 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -25,10 +25,12 @@ #include -#ifdef Q_OS_MAC - #include -#else - #include +#ifndef __mobile__ + #ifdef Q_OS_MAC + #include + #else + #include + #endif #endif QGC_LOGGING_CATEGORY(JoystickManagerLog, "JoystickManagerLog") @@ -44,6 +46,7 @@ JoystickManager::JoystickManager(QObject* parent) { QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); +#ifndef __mobile__ if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) { qWarning() << "Couldn't initialize SimpleDirectMediaLayer:" << SDL_GetError(); return; @@ -70,6 +73,7 @@ JoystickManager::JoystickManager(QObject* parent) qCDebug(JoystickManagerLog) << "\tSkipping duplicate" << name; } } +#endif if (!_name2JoystickMap.count()) { qCDebug(JoystickManagerLog) << "\tnone found"; @@ -86,6 +90,7 @@ JoystickManager::~JoystickManager() void JoystickManager::_setActiveJoystickFromSettings(void) { +#ifndef __mobile__ QSettings settings; settings.beginGroup(_settingsGroup); @@ -97,6 +102,7 @@ void JoystickManager::_setActiveJoystickFromSettings(void) setActiveJoystick(_name2JoystickMap.value(name, _name2JoystickMap.first())); settings.setValue(_settingsKeyActiveJoystick, _activeJoystick->name()); +#endif } Joystick* JoystickManager::activeJoystick(void) @@ -106,6 +112,9 @@ Joystick* JoystickManager::activeJoystick(void) void JoystickManager::setActiveJoystick(Joystick* joystick) { +#ifdef __mobile__ + Q_UNUSED(joystick) +#else QSettings settings; if (!_name2JoystickMap.contains(joystick->name())) { @@ -124,6 +133,7 @@ void JoystickManager::setActiveJoystick(Joystick* joystick) emit activeJoystickChanged(_activeJoystick); emit activeJoystickNameChanged(_activeJoystick->name()); +#endif } QVariantList JoystickManager::joysticks(void) @@ -144,7 +154,11 @@ QStringList JoystickManager::joystickNames(void) QString JoystickManager::activeJoystickName(void) { +#ifdef __mobile__ + return QString(); +#else return _activeJoystick ? _activeJoystick->name() : QString(); +#endif } void JoystickManager::setActiveJoystickName(const QString& name) diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 45e04e734edbd0bd556c43f8208ced3b0cac3dcd..ec798024452606ae123dd445c28f5f1a0fad9616 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -57,9 +57,6 @@ G_END_DECLS #include "QGCMessageBox.h" #include "MainWindow.h" #include "UDPLink.h" -#ifndef __ios__ -#include "SerialLink.h" -#endif #include "QGCSingleton.h" #include "LinkManager.h" #include "HomePositionManager.h" @@ -78,9 +75,6 @@ G_END_DECLS #include "PowerComponentController.h" #include "RadioComponentController.h" #include "ScreenToolsController.h" -#ifndef __mobile__ -#include "FirmwareUpgradeController.h" -#endif #include "AutoPilotPlugin.h" #include "VehicleComponent.h" #include "FirmwarePluginManager.h" @@ -90,10 +84,18 @@ G_END_DECLS #include "Vehicle.h" #include "MavlinkQmlSingleton.h" #include "JoystickManager.h" -#include "JoystickConfigController.h" + +#ifndef __ios__ + #include "SerialLink.h" +#endif + +#ifndef __mobile__ + #include "FirmwareUpgradeController.h" + #include "JoystickConfigController.h" +#endif #ifdef QGC_RTLAB_ENABLED -#include "OpalLink.h" + #include "OpalLink.h" #endif @@ -341,10 +343,10 @@ void QGCApplication::_initCommon(void) qmlRegisterType ("QGroundControl.Controllers", 1, 0, "PowerComponentController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "RadioComponentController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ScreenToolsController"); - qmlRegisterType ("QGroundControl.Controllers", 1, 0, "JoystickConfigController"); #ifndef __mobile__ qmlRegisterType("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController"); + qmlRegisterType ("QGroundControl.Controllers", 1, 0, "JoystickConfigController"); #endif // Register Qml Singletons diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index cdb54dfe06f7df3b89944efe7a7c44e920f81ffc..86e30aa91c2de7039a93f60b0c15048038221aa8 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -113,11 +113,13 @@ void MultiVehicleManager::_deleteVehiclePhase1(void) // Disconnect the vehicle from the uas vehicle->uas()->clearVehicle(); +#ifndef __mobile__ // Disconnect joystick Joystick* joystick = JoystickManager::instance()->activeJoystick(); if (joystick) { joystick->stopPolling(); } +#endif // First we must signal that a vehicle is no longer available. _activeVehicleAvailable = false; @@ -162,11 +164,13 @@ void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle) { if (vehicle != _activeVehicle) { if (_activeVehicle) { +#ifndef __mobile__ // Disconnect joystick Joystick* joystick = JoystickManager::instance()->activeJoystick(); if (joystick) { joystick->stopPolling(); } +#endif // The sequence of signals is very important in order to not leave Qml elements connected // to a non-existent vehicle. @@ -213,11 +217,13 @@ void MultiVehicleManager::_autopilotPluginReadyChanged(bool pluginReady) } if (autopilot->vehicle() == _activeVehicle) { +#ifndef __mobile__ // Connect joystick Joystick* joystick = JoystickManager::instance()->activeJoystick(); if (joystick && joystick->enabled()) { joystick->startPolling(); } +#endif _parameterReadyVehicleAvailable = pluginReady; emit parameterReadyVehicleAvailableChanged(pluginReady);