Commit 6e1bfc38 authored by Don Gagne's avatar Don Gagne

Make new Joystick code mobile friendly

parent 50085ece
......@@ -29,10 +29,12 @@
#include <QSettings>
#ifdef Q_OS_MAC
#include <SDL.h>
#else
#include <SDL/SDL.h>
#ifndef __mobile__
#ifdef Q_OS_MAC
#include <SDL.h>
#else
#include <SDL/SDL.h>
#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__
......@@ -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;
......
......@@ -25,10 +25,12 @@
#include <QQmlEngine>
#ifdef Q_OS_MAC
#include <SDL.h>
#else
#include <SDL/SDL.h>
#ifndef __mobile__
#ifdef Q_OS_MAC
#include <SDL.h>
#else
#include <SDL/SDL.h>
#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)
......
......@@ -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<PowerComponentController> ("QGroundControl.Controllers", 1, 0, "PowerComponentController");
qmlRegisterType<RadioComponentController> ("QGroundControl.Controllers", 1, 0, "RadioComponentController");
qmlRegisterType<ScreenToolsController> ("QGroundControl.Controllers", 1, 0, "ScreenToolsController");
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
#ifndef __mobile__
qmlRegisterType<FirmwareUpgradeController>("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController");
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
#endif
// Register Qml Singletons
......
......@@ -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);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment